From f34c57833efac168dce5dba587fd686e183f2e0c Mon Sep 17 00:00:00 2001 From: "bouwens.mehl@gmail.com" Date: Tue, 8 Jan 2013 20:05:49 +0000 Subject: [PATCH] Kalman filter integration git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@241 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61 --- src/baseflight/.cproject | 46 + src/baseflight/.project | 26 + src/baseflight/JLinkSettings.ini | 31 + src/baseflight/Makefile | 182 + src/baseflight/baseflight.uvproj | 2610 ++++++ .../lib/CMSIS/CM3/CoreSupport/core_cm3.c | 784 ++ .../lib/CMSIS/CM3/CoreSupport/core_cm3.h | 1818 ++++ .../ST/STM32F10x/Release_Notes.html | 284 + .../startup/TrueSTUDIO/startup_stm32f10x_cl.s | 473 + .../startup/TrueSTUDIO/startup_stm32f10x_hd.s | 469 + .../TrueSTUDIO/startup_stm32f10x_hd_vl.s | 451 + .../startup/TrueSTUDIO/startup_stm32f10x_ld.s | 347 + .../TrueSTUDIO/startup_stm32f10x_ld_vl.s | 392 + .../startup/TrueSTUDIO/startup_stm32f10x_md.s | 363 + .../TrueSTUDIO/startup_stm32f10x_md_vl.s | 408 + .../startup/TrueSTUDIO/startup_stm32f10x_xl.s | 467 + .../startup/arm/startup_stm32f10x_cl.s | 368 + .../startup/arm/startup_stm32f10x_hd.s | 358 + .../startup/arm/startup_stm32f10x_hd_vl.s | 346 + .../startup/arm/startup_stm32f10x_ld.s | 297 + .../startup/arm/startup_stm32f10x_ld_vl.s | 304 + .../startup/arm/startup_stm32f10x_md.s | 307 + .../startup/arm/startup_stm32f10x_md_vl.s | 315 + .../startup/arm/startup_stm32f10x_xl.s | 358 + .../startup/gcc_ride7/startup_stm32f10x_cl.s | 468 + .../startup/gcc_ride7/startup_stm32f10x_hd.s | 465 + .../gcc_ride7/startup_stm32f10x_hd_vl.s | 442 + .../startup/gcc_ride7/startup_stm32f10x_ld.s | 343 + .../gcc_ride7/startup_stm32f10x_ld_vl.s | 383 + .../startup/gcc_ride7/startup_stm32f10x_md.s | 358 + .../gcc_ride7/startup_stm32f10x_md_vl.s | 399 + .../startup/gcc_ride7/startup_stm32f10x_xl.s | 465 + .../startup/iar/startup_stm32f10x_cl.s | 507 + .../startup/iar/startup_stm32f10x_hd.s | 496 + .../startup/iar/startup_stm32f10x_hd_vl.s | 461 + .../startup/iar/startup_stm32f10x_ld.s | 366 + .../startup/iar/startup_stm32f10x_ld_vl.s | 369 + .../startup/iar/startup_stm32f10x_md.s | 391 + .../startup/iar/startup_stm32f10x_md_vl.s | 394 + .../startup/iar/startup_stm32f10x_xl.s | 496 + .../DeviceSupport/ST/STM32F10x/stm32f10x.h | 8336 +++++++++++++++++ .../ST/STM32F10x/stm32f10x_conf.h | 79 + .../ST/STM32F10x/system_stm32f10x.c | 256 + .../ST/STM32F10x/system_stm32f10x.h | 98 + .../lib/STM32F10x_StdPeriph_Driver/inc/misc.h | 220 + .../inc/stm32f10x_adc.h | 483 + .../inc/stm32f10x_bkp.h | 195 + .../inc/stm32f10x_can.h | 697 ++ .../inc/stm32f10x_cec.h | 210 + .../inc/stm32f10x_crc.h | 94 + .../inc/stm32f10x_dac.h | 317 + .../inc/stm32f10x_dbgmcu.h | 119 + .../inc/stm32f10x_dma.h | 439 + .../inc/stm32f10x_exti.h | 184 + .../inc/stm32f10x_flash.h | 426 + .../inc/stm32f10x_fsmc.h | 733 ++ .../inc/stm32f10x_gpio.h | 385 + .../inc/stm32f10x_i2c.h | 684 ++ .../inc/stm32f10x_iwdg.h | 140 + .../inc/stm32f10x_pwr.h | 156 + .../inc/stm32f10x_rcc.h | 727 ++ .../inc/stm32f10x_rtc.h | 135 + .../inc/stm32f10x_sdio.h | 531 ++ .../inc/stm32f10x_spi.h | 487 + .../inc/stm32f10x_tim.h | 1164 +++ .../inc/stm32f10x_usart.h | 412 + .../inc/stm32f10x_wwdg.h | 115 + .../lib/STM32F10x_StdPeriph_Driver/src/misc.c | 225 + .../src/stm32f10x_adc.c | 1307 +++ .../src/stm32f10x_bkp.c | 308 + .../src/stm32f10x_can.c | 1415 +++ .../src/stm32f10x_cec.c | 433 + .../src/stm32f10x_crc.c | 160 + .../src/stm32f10x_dac.c | 571 ++ .../src/stm32f10x_dbgmcu.c | 162 + .../src/stm32f10x_dma.c | 714 ++ .../src/stm32f10x_exti.c | 269 + .../src/stm32f10x_flash.c | 1684 ++++ .../src/stm32f10x_fsmc.c | 866 ++ .../src/stm32f10x_gpio.c | 650 ++ .../src/stm32f10x_i2c.c | 1331 +++ .../src/stm32f10x_iwdg.c | 190 + .../src/stm32f10x_pwr.c | 307 + .../src/stm32f10x_rcc.c | 1470 +++ .../src/stm32f10x_rtc.c | 339 + .../src/stm32f10x_sdio.c | 799 ++ .../src/stm32f10x_spi.c | 908 ++ .../src/stm32f10x_tim.c | 2890 ++++++ .../src/stm32f10x_usart.c | 1058 +++ .../src/stm32f10x_wwdg.c | 224 + src/baseflight/obj/baseflight.hex | 3153 +++++++ src/baseflight/obj/baseflight_fy90q.hex | 2540 +++++ .../startup_stm32f10x_md.s | 349 + .../startup_stm32f10x_md_fy90q.s | 359 + .../startup_stm32f10x_md_gcc.S | 410 + src/baseflight/src/board.h | 169 + src/baseflight/src/buzzer.c | 128 + src/baseflight/src/cli.c | 851 ++ src/baseflight/src/config.c | 312 + src/baseflight/src/drv_adc.c | 60 + src/baseflight/src/drv_adc.h | 15 + src/baseflight/src/drv_adc_fy90q.c | 144 + src/baseflight/src/drv_adxl345.c | 110 + src/baseflight/src/drv_adxl345.h | 8 + src/baseflight/src/drv_bmp085.c | 296 + src/baseflight/src/drv_bmp085.h | 3 + src/baseflight/src/drv_hcsr04.c | 132 + src/baseflight/src/drv_hcsr04.h | 9 + src/baseflight/src/drv_hmc5883l.c | 87 + src/baseflight/src/drv_hmc5883l.h | 7 + src/baseflight/src/drv_i2c.c | 356 + src/baseflight/src/drv_i2c.h | 7 + src/baseflight/src/drv_i2c_soft.c | 215 + src/baseflight/src/drv_l3g4200d.c | 98 + src/baseflight/src/drv_l3g4200d.h | 4 + src/baseflight/src/drv_ledring.c | 53 + src/baseflight/src/drv_ledring.h | 5 + src/baseflight/src/drv_mma845x.c | 110 + src/baseflight/src/drv_mma845x.h | 3 + src/baseflight/src/drv_mpu3050.c | 118 + src/baseflight/src/drv_mpu3050.h | 4 + src/baseflight/src/drv_mpu6050.c | 763 ++ src/baseflight/src/drv_mpu6050.h | 5 + src/baseflight/src/drv_ms5611.c | 180 + src/baseflight/src/drv_ms5611.h | 3 + src/baseflight/src/drv_pwm.c | 507 + src/baseflight/src/drv_pwm.h | 52 + src/baseflight/src/drv_pwm_fy90q.c | 334 + src/baseflight/src/drv_system.c | 171 + src/baseflight/src/drv_system.h | 14 + src/baseflight/src/drv_uart.c | 245 + src/baseflight/src/drv_uart.h | 16 + src/baseflight/src/gps.c | 1087 +++ src/baseflight/src/imu.c | 411 + src/baseflight/src/main.c | 156 + src/baseflight/src/mixer.c | 387 + src/baseflight/src/mw.c | 648 ++ src/baseflight/src/mw.h | 387 + src/baseflight/src/printf.c | 248 + src/baseflight/src/printf.h | 121 + src/baseflight/src/sensors.c | 561 ++ src/baseflight/src/serial.c | 462 + src/baseflight/src/spektrum.c | 87 + src/baseflight/src/telemetry.c | 202 + src/baseflight/stm32_flash.ld | 150 + src/baseflight/support/flash.bat | 26 + src/baseflight/support/stmloader/Makefile | 14 + src/baseflight/support/stmloader/loader.c | 116 + src/baseflight/support/stmloader/serial.c | 179 + src/baseflight/support/stmloader/serial.h | 38 + .../support/stmloader/stmbootloader.c | 341 + .../support/stmloader/stmbootloader.h | 27 + 152 files changed, 72762 insertions(+) create mode 100644 src/baseflight/.cproject create mode 100644 src/baseflight/.project create mode 100755 src/baseflight/JLinkSettings.ini create mode 100644 src/baseflight/Makefile create mode 100755 src/baseflight/baseflight.uvproj create mode 100755 src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.c create mode 100755 src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.h create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c create mode 100755 src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/misc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/misc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c create mode 100755 src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c create mode 100644 src/baseflight/obj/baseflight.hex create mode 100644 src/baseflight/obj/baseflight_fy90q.hex create mode 100644 src/baseflight/src/baseflight_startups/startup_stm32f10x_md.s create mode 100644 src/baseflight/src/baseflight_startups/startup_stm32f10x_md_fy90q.s create mode 100644 src/baseflight/src/baseflight_startups/startup_stm32f10x_md_gcc.S create mode 100755 src/baseflight/src/board.h create mode 100644 src/baseflight/src/buzzer.c create mode 100644 src/baseflight/src/cli.c create mode 100755 src/baseflight/src/config.c create mode 100755 src/baseflight/src/drv_adc.c create mode 100755 src/baseflight/src/drv_adc.h create mode 100644 src/baseflight/src/drv_adc_fy90q.c create mode 100755 src/baseflight/src/drv_adxl345.c create mode 100755 src/baseflight/src/drv_adxl345.h create mode 100755 src/baseflight/src/drv_bmp085.c create mode 100755 src/baseflight/src/drv_bmp085.h create mode 100644 src/baseflight/src/drv_hcsr04.c create mode 100644 src/baseflight/src/drv_hcsr04.h create mode 100755 src/baseflight/src/drv_hmc5883l.c create mode 100755 src/baseflight/src/drv_hmc5883l.h create mode 100755 src/baseflight/src/drv_i2c.c create mode 100755 src/baseflight/src/drv_i2c.h create mode 100644 src/baseflight/src/drv_i2c_soft.c create mode 100644 src/baseflight/src/drv_l3g4200d.c create mode 100644 src/baseflight/src/drv_l3g4200d.h create mode 100644 src/baseflight/src/drv_ledring.c create mode 100644 src/baseflight/src/drv_ledring.h create mode 100644 src/baseflight/src/drv_mma845x.c create mode 100644 src/baseflight/src/drv_mma845x.h create mode 100755 src/baseflight/src/drv_mpu3050.c create mode 100755 src/baseflight/src/drv_mpu3050.h create mode 100644 src/baseflight/src/drv_mpu6050.c create mode 100644 src/baseflight/src/drv_mpu6050.h create mode 100644 src/baseflight/src/drv_ms5611.c create mode 100644 src/baseflight/src/drv_ms5611.h create mode 100755 src/baseflight/src/drv_pwm.c create mode 100755 src/baseflight/src/drv_pwm.h create mode 100644 src/baseflight/src/drv_pwm_fy90q.c create mode 100755 src/baseflight/src/drv_system.c create mode 100755 src/baseflight/src/drv_system.h create mode 100755 src/baseflight/src/drv_uart.c create mode 100755 src/baseflight/src/drv_uart.h create mode 100644 src/baseflight/src/gps.c create mode 100755 src/baseflight/src/imu.c create mode 100755 src/baseflight/src/main.c create mode 100755 src/baseflight/src/mixer.c create mode 100755 src/baseflight/src/mw.c create mode 100755 src/baseflight/src/mw.h create mode 100644 src/baseflight/src/printf.c create mode 100644 src/baseflight/src/printf.h create mode 100755 src/baseflight/src/sensors.c create mode 100755 src/baseflight/src/serial.c create mode 100644 src/baseflight/src/spektrum.c create mode 100644 src/baseflight/src/telemetry.c create mode 100644 src/baseflight/stm32_flash.ld create mode 100644 src/baseflight/support/flash.bat create mode 100644 src/baseflight/support/stmloader/Makefile create mode 100644 src/baseflight/support/stmloader/loader.c create mode 100644 src/baseflight/support/stmloader/serial.c create mode 100644 src/baseflight/support/stmloader/serial.h create mode 100644 src/baseflight/support/stmloader/stmbootloader.c create mode 100644 src/baseflight/support/stmloader/stmbootloader.h diff --git a/src/baseflight/.cproject b/src/baseflight/.cproject new file mode 100644 index 0000000000..ad482da6e5 --- /dev/null +++ b/src/baseflight/.cproject @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/baseflight/.project b/src/baseflight/.project new file mode 100644 index 0000000000..1668e4230e --- /dev/null +++ b/src/baseflight/.project @@ -0,0 +1,26 @@ + + + TimecopsSVN + + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/src/baseflight/JLinkSettings.ini b/src/baseflight/JLinkSettings.ini new file mode 100755 index 0000000000..f320c7ce1a --- /dev/null +++ b/src/baseflight/JLinkSettings.ini @@ -0,0 +1,31 @@ +[BREAKPOINTS] +ShowInfoWin = 1 +EnableFlashBP = 2 +BPDuringExecution = 0 +[CFI] +CFISize = 0x00 +CFIAddr = 0x00 +[CPU] +OverrideMemMap = 0 +AllowSimulation = 1 +ScriptFile="" +[FLASH] +MinNumBytesFlashDL = 0 +SkipProgOnCRCMatch = 1 +VerifyDownload = 1 +AllowCaching = 1 +EnableFlashDL = 2 +Override = 0 +Device="AD7160" +[GENERAL] +WorkRAMSize = 0x00 +WorkRAMAddr = 0x00 +[SWO] +SWOLogFile="" +[MEM] +RdOverrideOrMask = 0x00 +RdOverrideAndMask = 0xFFFFFFFF +RdOverrideAddr = 0xFFFFFFFF +WrOverrideOrMask = 0x00 +WrOverrideAndMask = 0xFFFFFFFF +WrOverrideAddr = 0xFFFFFFFF diff --git a/src/baseflight/Makefile b/src/baseflight/Makefile new file mode 100644 index 0000000000..8477761c7e --- /dev/null +++ b/src/baseflight/Makefile @@ -0,0 +1,182 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return +############################################################################### +# +# Makefile for building the baseflight firmware. +# +# Invoke this with 'make help' to see the list of supported targets. +# + +############################################################################### +# Things that the user might override on the commandline +# + +# The target to build, must be one of NAZE or FY90Q +TARGET ?= NAZE + +# Compile-time options +OPTIONS ?= + +############################################################################### +# Things that need to be maintained as the source changes +# + +VALID_TARGETS = NAZE FY90Q + +# Working directories +ROOT = $(dir $(lastword $(MAKEFILE_LIST))) +SRC_DIR = $(ROOT)/src +CMSIS_DIR = $(ROOT)/lib/CMSIS +STDPERIPH_DIR = $(ROOT)/lib/STM32F10x_StdPeriph_Driver +OBJECT_DIR = $(ROOT)/obj +BIN_DIR = $(ROOT)/obj + +# Source files common to all targets +COMMON_SRC = startup_stm32f10x_md_gcc.S \ + buzzer.c \ + cli.c \ + config.c \ + gps.c \ + imu.c \ + main.c \ + mixer.c \ + mw.c \ + sensors.c \ + serial.c \ + spektrum.c \ + telemetry.c \ + drv_i2c.c \ + drv_i2c_soft.c \ + drv_system.c \ + drv_uart.c \ + printf.c \ + $(CMSIS_SRC) \ + $(STDPERIPH_SRC) + +# Source files for the NAZE target +NAZE_SRC = drv_adc.c \ + drv_adxl345.c \ + drv_bmp085.c \ + drv_ms5611.c \ + drv_hcsr04.c \ + drv_hmc5883l.c \ + drv_ledring.c \ + drv_mma845x.c \ + drv_mpu3050.c \ + drv_mpu6050.c \ + drv_l3g4200d.c \ + drv_pwm.c \ + $(COMMON_SRC) + +# Source files for the FY90Q target +FY90Q_SRC = drv_adc_fy90q.c \ + drv_pwm_fy90q.c \ + $(COMMON_SRC) + +# Search path for baseflight sources +VPATH := $(SRC_DIR):$(SRC_DIR)/baseflight_startups + +# Search path and source files for the CMSIS sources +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) + +############################################################################### +# Things that might need changing to use different tools +# + +# Tool names +CC = arm-none-eabi-gcc +OBJCOPY = arm-none-eabi-objcopy + +# +# Tool options. +# +INCLUDE_DIRS = $(SRC_DIR) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 +CFLAGS = $(ARCH_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + -Os \ + -Wall \ + -ffunction-sections \ + -fdata-sections \ + -DSTM32F10X_MD \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) + +ASFLAGS = $(ARCH_FLAGS) \ + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) + +# XXX Map/crossref output? +LD_SCRIPT = $(ROOT)/stm32_flash.ld +LDFLAGS = -lm \ + $(ARCH_FLAGS) \ + -static \ + -Wl,-gc-sections \ + -T$(LD_SCRIPT) + +############################################################################### +# No user-serviceable parts below +############################################################################### + +# +# Things we will build +# +ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) +$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) +endif + +TARGET_HEX = $(BIN_DIR)/baseflight_$(TARGET).hex +TARGET_ELF = $(BIN_DIR)/baseflight_$(TARGET).elf +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(OBJCOPY) -O ihex $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(CC) -o $@ $^ $(LDFLAGS) + +# Compile +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(CFLAGS) $< + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.s + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< +$(OBJECT_DIR)/$(TARGET)/%.o): %.S + @mkdir -p $(dir $@) + @echo %% $(notdir $<) + @$(CC) -c -o $@ $(ASFLAGS) $< + +clean: + rm -f $(TARGET_HEX) $(TARGET_ELF) $(TARGET_OBJS) + +help: + @echo "" + @echo "Makefile for the baseflight firmware" + @echo "" + @echo "Usage:" + @echo " make [TARGET=] [OPTIONS=\"\"]" + @echo "" + @echo "Valid TARGET values are: $(VALID_TARGETS)" + @echo "" diff --git a/src/baseflight/baseflight.uvproj b/src/baseflight/baseflight.uvproj new file mode 100755 index 0000000000..378859f85b --- /dev/null +++ b/src/baseflight/baseflight.uvproj @@ -0,0 +1,2610 @@ + + + + 1.1 + +
### uVision Project, (C) Keil Software
+ + + + STM32 + 0x4 + ARM-ADS + + + STM32F103CB + STMicroelectronics + IRAM(0x20000000-0x20004FFF) IROM(0x8000000-0x801FFFF) CLOCK(8000000) CPUTYPE("Cortex-M3") + + "STARTUP\ST\STM32F10x\startup_stm32f10x_md.s" ("STM32 Medium Density Line Startup Code") + UL2CM3(-O14 -S0 -C0 -N00("ARM Cortex-M3") -D00(1BA00477) -L00(4) -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL020000) + 4401 + stm32f10x.h + + + + + + + + + + SFD\ST\STM32F1xx\STM32F103xx.sfr + 0 + + + + ST\STM32F10x\ + ST\STM32F10x\ + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + baseflight + 1 + 0 + 1 + 1 + 1 + .\obj\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + + + SARMCM3.DLL + + DARMSTM.DLL + -pSTM32F103CB + SARMCM3.DLL + + TARMSTM.DLL + -pSTM32F103CB + + + + 1 + 0 + 0 + 0 + 16 + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 0 + + 0 + 1 + + + + + + + + + + + + + + BIN\UL2CM3.DLL + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + BIN\UL2CM3.DLL + + + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M3" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 8 + 1 + 0 + 0 + 3 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 1 + 0x8000000 + 0x20000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x20000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 0 + 0 + + + STM32F10X_MD,USE_STDPERIPH_DRIVER + + lib\CMSIS\CM3\CoreSupport;lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x;lib\STM32F10x_StdPeriph_Driver\inc + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + + + + + + + + App + + + cli.c + 1 + .\src\cli.c + + + config.c + 1 + .\src\config.c + + + imu.c + 1 + .\src\imu.c + + + main.c + 1 + .\src\main.c + + + mixer.c + 1 + .\src\mixer.c + + + mw.c + 1 + .\src\mw.c + + + sensors.c + 1 + .\src\sensors.c + + + serial.c + 1 + .\src\serial.c + + + board.h + 5 + .\src\board.h + + + mw.h + 5 + .\src\mw.h + + + gps.c + 1 + .\src\gps.c + + + spektrum.c + 1 + .\src\spektrum.c + + + buzzer.c + 1 + .\src\buzzer.c + + + telemetry.c + 1 + .\src\telemetry.c + + + + + Drivers + + + drv_adc.c + 1 + .\src\drv_adc.c + + + drv_adxl345.c + 1 + .\src\drv_adxl345.c + + + drv_bmp085.c + 1 + .\src\drv_bmp085.c + + + drv_hmc5883l.c + 1 + .\src\drv_hmc5883l.c + + + drv_i2c.c + 1 + .\src\drv_i2c.c + + + drv_mpu3050.c + 1 + .\src\drv_mpu3050.c + + + drv_pwm.c + 1 + .\src\drv_pwm.c + + + drv_system.c + 1 + .\src\drv_system.c + + + drv_uart.c + 1 + .\src\drv_uart.c + + + drv_ledring.c + 1 + .\src\drv_ledring.c + + + drv_mpu6050.c + 1 + .\src\drv_mpu6050.c + + + drv_adc_fy90q.c + 1 + .\src\drv_adc_fy90q.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_pwm_fy90q.c + 1 + .\src\drv_pwm_fy90q.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_mma845x.c + 1 + .\src\drv_mma845x.c + + + drv_hcsr04.c + 1 + .\src\drv_hcsr04.c + + + drv_i2c_soft.c + 1 + .\src\drv_i2c_soft.c + + + drv_l3g4200d.c + 1 + .\src\drv_l3g4200d.c + + + drv_ms5611.c + 1 + .\src\drv_ms5611.c + + + + + System + + + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 4 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + core_cm3.c + 1 + .\lib\CMSIS\CM3\CoreSupport\core_cm3.c + + + system_stm32f10x.c + 1 + .\lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c + + + misc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\misc.c + + + stm32f10x_adc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c + + + stm32f10x_dma.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c + + + stm32f10x_exti.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c + + + stm32f10x_i2c.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c + + + stm32f10x_rcc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c + + + stm32f10x_tim.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c + + + stm32f10x_usart.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c + + + stm32f10x_gpio.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c + + + stm32f10x_flash.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + + + startup_stm32f10x_md.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md.s + + + startup_stm32f10x_md_fy90q.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md_fy90q.s + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + printf.c + 1 + .\src\printf.c + + + + + + + STM32-Release + 0x4 + ARM-ADS + + + STM32F103C8 + STMicroelectronics + IRAM(0x20000000-0x20004FFF) IROM(0x8000000-0x800FFFF) CLOCK(8000000) CPUTYPE("Cortex-M3") + + "STARTUP\ST\STM32F10x\startup_stm32f10x_md.s" ("STM32 Medium Density Line Startup Code") + UL2CM3(-O14 -S0 -C0 -N00("ARM Cortex-M3") -D00(1BA00477) -L00(4) -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL010000) + 4235 + stm32f10x.h + + + + + + + + + + SFD\ST\STM32F1xx\STM32F103xx.sfrSVD=SFD\ST\STM32F1xx\STM32F103xx.sfr + 0 + + + + ST\STM32F10x\ + ST\STM32F10x\ + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + baseflight + 1 + 0 + 1 + 1 + 1 + .\obj\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + + + SARMCM3.DLL + + DARMSTM.DLL + -pSTM32F103C8 + SARMCM3.DLL + + TARMSTM.DLL + -pSTM32F103C8 + + + + 1 + 0 + 0 + 0 + 16 + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 0 + + 0 + 1 + + + + + + + + + + + + + + BIN\UL2CM3.DLL + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + BIN\UL2CM3.DLL + + + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + "Cortex-M3" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 8 + 1 + 0 + 0 + 3 + 3 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 1 + 0x8000000 + 0x10000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x10000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 4 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 2 + 0 + 0 + + + STM32F10X_MD,USE_STDPERIPH_DRIVER + + CoOS\portable;CoOS\kernel;lib\CMSIS\CM3\CoreSupport;lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x;lib\STM32F10x_StdPeriph_Driver\inc + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + + + + + + + + App + + + cli.c + 1 + .\src\cli.c + + + config.c + 1 + .\src\config.c + + + imu.c + 1 + .\src\imu.c + + + main.c + 1 + .\src\main.c + + + mixer.c + 1 + .\src\mixer.c + + + mw.c + 1 + .\src\mw.c + + + sensors.c + 1 + .\src\sensors.c + + + serial.c + 1 + .\src\serial.c + + + board.h + 5 + .\src\board.h + + + mw.h + 5 + .\src\mw.h + + + gps.c + 1 + .\src\gps.c + + + spektrum.c + 1 + .\src\spektrum.c + + + buzzer.c + 1 + .\src\buzzer.c + + + telemetry.c + 1 + .\src\telemetry.c + + + + + Drivers + + + drv_adc.c + 1 + .\src\drv_adc.c + + + drv_adxl345.c + 1 + .\src\drv_adxl345.c + + + drv_bmp085.c + 1 + .\src\drv_bmp085.c + + + drv_hmc5883l.c + 1 + .\src\drv_hmc5883l.c + + + drv_i2c.c + 1 + .\src\drv_i2c.c + + + drv_mpu3050.c + 1 + .\src\drv_mpu3050.c + + + drv_pwm.c + 1 + .\src\drv_pwm.c + + + drv_system.c + 1 + .\src\drv_system.c + + + drv_uart.c + 1 + .\src\drv_uart.c + + + drv_ledring.c + 1 + .\src\drv_ledring.c + + + drv_mpu6050.c + 1 + .\src\drv_mpu6050.c + + + drv_adc_fy90q.c + 1 + .\src\drv_adc_fy90q.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_pwm_fy90q.c + 1 + .\src\drv_pwm_fy90q.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_mma845x.c + 1 + .\src\drv_mma845x.c + + + drv_hcsr04.c + 1 + .\src\drv_hcsr04.c + + + drv_i2c_soft.c + 1 + .\src\drv_i2c_soft.c + + + drv_l3g4200d.c + 1 + .\src\drv_l3g4200d.c + + + drv_ms5611.c + 1 + .\src\drv_ms5611.c + + + + + System + + + core_cm3.c + 1 + .\lib\CMSIS\CM3\CoreSupport\core_cm3.c + + + system_stm32f10x.c + 1 + .\lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c + + + misc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\misc.c + + + stm32f10x_adc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c + + + stm32f10x_dma.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c + + + stm32f10x_exti.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c + + + stm32f10x_i2c.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c + + + stm32f10x_rcc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c + + + stm32f10x_tim.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c + + + stm32f10x_usart.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c + + + stm32f10x_gpio.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c + + + stm32f10x_flash.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + + + startup_stm32f10x_md.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md.s + + + startup_stm32f10x_md_fy90q.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md_fy90q.s + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + printf.c + 1 + .\src\printf.c + + + + + + + STM32-FY90Q + 0x4 + ARM-ADS + + + STM32F103RB + STMicroelectronics + IRAM(0x20000000-0x20004FFF) IROM(0x8000000-0x801FFFF) CLOCK(8000000) CPUTYPE("Cortex-M3") + + "STARTUP\ST\STM32F10x\startup_stm32f10x_md.s" ("STM32 Medium Density Line Startup Code") + UL2CM3(-O14 -S0 -C0 -N00("ARM Cortex-M3") -D00(1BA00477) -L00(4) -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F10x_128 -FS08000000 -FL020000) + 4231 + stm32f10x_md.h + + + + + + + + + + SFD\ST\STM32F10xx\STM32F10xxB.sfr + 0 + + + + ST\STM32F10x\ + ST\STM32F10x\ + + 0 + 0 + 0 + 0 + 1 + + .\obj\ + baseflight_fy90q + 1 + 0 + 1 + 1 + 1 + .\obj\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + + + SARMCM3.DLL + + DARMSTM.DLL + -pSTM32F103RB + SARMCM3.DLL + + TARMSTM.DLL + -pSTM32F103RB + + + + 1 + 0 + 0 + 0 + 16 + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 0 + + 0 + 1 + + + + + + + + + + + + + + BIN\UL2CM3.DLL + + + + + 1 + 0 + 0 + 1 + 1 + 4096 + + BIN\UL2CM3.DLL + "" () + + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M3" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 8 + 1 + 0 + 0 + 3 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 1 + 0x8000000 + 0x20000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x8000000 + 0x20000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x5000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + STM32F10X_MD,USE_STDPERIPH_DRIVER,FY90Q + + lib\CMSIS\CM3\CoreSupport;lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x;lib\STM32F10x_StdPeriph_Driver\inc + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 1 + 0 + 0 + 0 + 1 + 0 + 0x08000000 + 0x20000000 + + + + + + + + + + + + App + + + cli.c + 1 + .\src\cli.c + + + config.c + 1 + .\src\config.c + + + imu.c + 1 + .\src\imu.c + + + main.c + 1 + .\src\main.c + + + mixer.c + 1 + .\src\mixer.c + + + mw.c + 1 + .\src\mw.c + + + sensors.c + 1 + .\src\sensors.c + + + serial.c + 1 + .\src\serial.c + + + board.h + 5 + .\src\board.h + + + mw.h + 5 + .\src\mw.h + + + gps.c + 1 + .\src\gps.c + + + spektrum.c + 1 + .\src\spektrum.c + + + buzzer.c + 1 + .\src\buzzer.c + + + telemetry.c + 1 + .\src\telemetry.c + + + + + Drivers + + + drv_adc.c + 1 + .\src\drv_adc.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_adxl345.c + 1 + .\src\drv_adxl345.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_bmp085.c + 1 + .\src\drv_bmp085.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_hmc5883l.c + 1 + .\src\drv_hmc5883l.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_i2c.c + 1 + .\src\drv_i2c.c + + + drv_mpu3050.c + 1 + .\src\drv_mpu3050.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_pwm.c + 1 + .\src\drv_pwm.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_system.c + 1 + .\src\drv_system.c + + + drv_uart.c + 1 + .\src\drv_uart.c + + + drv_ledring.c + 1 + .\src\drv_ledring.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_mpu6050.c + 1 + .\src\drv_mpu6050.c + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 0 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + + + + drv_adc_fy90q.c + 1 + .\src\drv_adc_fy90q.c + + + drv_pwm_fy90q.c + 1 + .\src\drv_pwm_fy90q.c + + + drv_mma845x.c + 1 + .\src\drv_mma845x.c + + + drv_hcsr04.c + 1 + .\src\drv_hcsr04.c + + + drv_i2c_soft.c + 1 + .\src\drv_i2c_soft.c + + + drv_l3g4200d.c + 1 + .\src\drv_l3g4200d.c + + + drv_ms5611.c + 1 + .\src\drv_ms5611.c + + + + + System + + + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 4 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 0 + 2 + 2 + + + + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + core_cm3.c + 1 + .\lib\CMSIS\CM3\CoreSupport\core_cm3.c + + + system_stm32f10x.c + 1 + .\lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c + + + misc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\misc.c + + + stm32f10x_adc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c + + + stm32f10x_dma.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c + + + stm32f10x_exti.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c + + + stm32f10x_i2c.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c + + + stm32f10x_rcc.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c + + + stm32f10x_tim.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c + + + stm32f10x_usart.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c + + + stm32f10x_gpio.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c + + + stm32f10x_flash.c + 1 + .\lib\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + + + startup_stm32f10x_md.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md.s + + + 2 + 0 + 0 + 0 + 0 + 0 + 2 + 2 + 2 + 2 + 11 + + + + + + 2 + 2 + 2 + 2 + 2 + 2 + 2 + 2 + + + + + + + + + + + + startup_stm32f10x_md_fy90q.s + 2 + .\src\baseflight_startups\startup_stm32f10x_md_fy90q.s + + + printf.c + 1 + .\src\printf.c + + + + + + + +
diff --git a/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.c b/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.c new file mode 100755 index 0000000000..0e8c3c43c8 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.c @@ -0,0 +1,784 @@ +/**************************************************************************//** + * @file core_cm3.c + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File + * @version V1.30 + * @date 30. October 2009 + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#include + +/* define compiler specific symbols */ +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +__ASM uint32_t __get_PSP(void) +{ + mrs r0, psp + bx lr +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +__ASM void __set_PSP(uint32_t topOfProcStack) +{ + msr psp, r0 + bx lr +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +__ASM uint32_t __get_MSP(void) +{ + mrs r0, msp + bx lr +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +__ASM void __set_MSP(uint32_t mainStackPointer) +{ + msr msp, r0 + bx lr +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +__ASM uint32_t __REV16(uint16_t value) +{ + rev16 r0, r0 + bx lr +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +__ASM int32_t __REVSH(int16_t value) +{ + revsh r0, r0 + bx lr +} + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +__ASM void __CLREX(void) +{ + clrex +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +__ASM uint32_t __get_BASEPRI(void) +{ + mrs r0, basepri + bx lr +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +__ASM void __set_BASEPRI(uint32_t basePri) +{ + msr basepri, r0 + bx lr +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +__ASM uint32_t __get_PRIMASK(void) +{ + mrs r0, primask + bx lr +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +__ASM void __set_PRIMASK(uint32_t priMask) +{ + msr primask, r0 + bx lr +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +__ASM uint32_t __get_FAULTMASK(void) +{ + mrs r0, faultmask + bx lr +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +__ASM void __set_FAULTMASK(uint32_t faultMask) +{ + msr faultmask, r0 + bx lr +} + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +__ASM uint32_t __get_CONTROL(void) +{ + mrs r0, control + bx lr +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +__ASM void __set_CONTROL(uint32_t control) +{ + msr control, r0 + bx lr +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ +#pragma diag_suppress=Pe940 + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) +{ + __ASM("mrs r0, psp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM("msr psp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) +{ + __ASM("mrs r0, msp"); + __ASM("bx lr"); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM("msr msp, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + __ASM("rev16 r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + __ASM("rbit r0, r0"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit values) + */ +uint8_t __LDREXB(uint8_t *addr) +{ + __ASM("ldrexb r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + __ASM("ldrexh r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + __ASM("ldrex r0, [r0]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + __ASM("strexb r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + __ASM("strexh r0, r0, [r1]"); + __ASM("bx lr"); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + __ASM("strex r0, r0, [r1]"); + __ASM("bx lr"); +} + +#pragma diag_default=Pe940 + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +uint32_t __get_PSP(void) __attribute__( ( naked ) ); +uint32_t __get_PSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, psp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) ); +void __set_PSP(uint32_t topOfProcStack) +{ + __ASM volatile ("MSR psp, %0\n\t" + "BX lr \n\t" : : "r" (topOfProcStack) ); +} + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +uint32_t __get_MSP(void) __attribute__( ( naked ) ); +uint32_t __get_MSP(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, msp\n\t" + "MOV r0, %0 \n\t" + "BX lr \n\t" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) ); +void __set_MSP(uint32_t topOfMainStack) +{ + __ASM volatile ("MSR msp, %0\n\t" + "BX lr \n\t" : : "r" (topOfMainStack) ); +} + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +uint32_t __get_BASEPRI(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, basepri_max" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +void __set_BASEPRI(uint32_t value) +{ + __ASM volatile ("MSR basepri, %0" : : "r" (value) ); +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +uint32_t __get_PRIMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, primask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +void __set_PRIMASK(uint32_t priMask) +{ + __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +uint32_t __get_FAULTMASK(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +void __set_FAULTMASK(uint32_t faultMask) +{ + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); +} + +/** + * @brief Return the Control Register value +* +* @return Control value + * + * Return the content of the control register + */ +uint32_t __get_CONTROL(void) +{ + uint32_t result=0; + + __ASM volatile ("MRS %0, control" : "=r" (result) ); + return(result); +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +void __set_CONTROL(uint32_t control) +{ + __ASM volatile ("MSR control, %0" : : "r" (control) ); +} + + +/** + * @brief Reverse byte order in integer value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in integer value + */ +uint32_t __REV(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +uint32_t __REV16(uint16_t value) +{ + uint32_t result=0; + + __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +int32_t __REVSH(int16_t value) +{ + uint32_t result=0; + + __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +uint32_t __RBIT(uint32_t value) +{ + uint32_t result=0; + + __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); + return(result); +} + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit value + */ +uint8_t __LDREXB(uint8_t *addr) +{ + uint8_t result=0; + + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +uint16_t __LDREXH(uint16_t *addr) +{ + uint16_t result=0; + + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +uint32_t __LDREXW(uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + return(result); +} + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +uint32_t __STREXB(uint8_t value, uint8_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +uint32_t __STREXH(uint16_t value, uint16_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + return(result); +} + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +uint32_t __STREXW(uint32_t value, uint32_t *addr) +{ + uint32_t result=0; + + __ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) ); + return(result); +} + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif diff --git a/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.h b/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.h new file mode 100755 index 0000000000..2b6b51a7d5 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/CoreSupport/core_cm3.h @@ -0,0 +1,1818 @@ +/**************************************************************************//** + * @file core_cm3.h + * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File + * @version V1.30 + * @date 30. October 2009 + * + * @note + * Copyright (C) 2009 ARM Limited. All rights reserved. + * + * @par + * ARM Limited (ARM) is supplying this software for use with Cortex-M + * processor based microcontrollers. This file can be freely distributed + * within development tools that are supporting such ARM based processors. + * + * @par + * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED + * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. + * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR + * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. + * + ******************************************************************************/ + +#ifndef __CM3_CORE_H__ +#define __CM3_CORE_H__ + +/** @addtogroup CMSIS_CM3_core_LintCinfiguration CMSIS CM3 Core Lint Configuration + * + * List of Lint messages which will be suppressed and not shown: + * - Error 10: \n + * register uint32_t __regBasePri __asm("basepri"); \n + * Error 10: Expecting ';' + * . + * - Error 530: \n + * return(__regBasePri); \n + * Warning 530: Symbol '__regBasePri' (line 264) not initialized + * . + * - Error 550: \n + * __regBasePri = (basePri & 0x1ff); \n + * Warning 550: Symbol '__regBasePri' (line 271) not accessed + * . + * - Error 754: \n + * uint32_t RESERVED0[24]; \n + * Info 754: local structure member '' (line 109, file ./cm3_core.h) not referenced + * . + * - Error 750: \n + * #define __CM3_CORE_H__ \n + * Info 750: local macro '__CM3_CORE_H__' (line 43, file./cm3_core.h) not referenced + * . + * - Error 528: \n + * static __INLINE void NVIC_DisableIRQ(uint32_t IRQn) \n + * Warning 528: Symbol 'NVIC_DisableIRQ(unsigned int)' (line 419, file ./cm3_core.h) not referenced + * . + * - Error 751: \n + * } InterruptType_Type; \n + * Info 751: local typedef 'InterruptType_Type' (line 170, file ./cm3_core.h) not referenced + * . + * Note: To re-enable a Message, insert a space before 'lint' * + * + */ + +/*lint -save */ +/*lint -e10 */ +/*lint -e530 */ +/*lint -e550 */ +/*lint -e754 */ +/*lint -e750 */ +/*lint -e528 */ +/*lint -e751 */ + + +/** @addtogroup CMSIS_CM3_core_definitions CM3 Core Definitions + This file defines all structures and symbols for CMSIS core: + - CMSIS version number + - Cortex-M core registers and bitfields + - Cortex-M core peripheral base address + @{ + */ + +#ifdef __cplusplus + extern "C" { +#endif + +#define __CM3_CMSIS_VERSION_MAIN (0x01) /*!< [31:16] CMSIS HAL main version */ +#define __CM3_CMSIS_VERSION_SUB (0x30) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | __CM3_CMSIS_VERSION_SUB) /*!< CMSIS HAL version number */ + +#define __CORTEX_M (0x03) /*!< Cortex core */ + +#include /* Include standard types */ + +#if defined (__ICCARM__) + #include /* IAR Intrinsics */ +#endif + + +#ifndef __NVIC_PRIO_BITS + #define __NVIC_PRIO_BITS 4 /*!< standard definition for NVIC Priority Bits */ +#endif + + + + +/** + * IO definitions + * + * define access restrictions to peripheral registers + */ + +#ifdef __cplusplus + #define __I volatile /*!< defines 'read only' permissions */ +#else + #define __I volatile const /*!< defines 'read only' permissions */ +#endif +#define __O volatile /*!< defines 'write only' permissions */ +#define __IO volatile /*!< defines 'read / write' permissions */ + + + +/******************************************************************************* + * Register Abstraction + ******************************************************************************/ +/** @addtogroup CMSIS_CM3_core_register CMSIS CM3 Core Register + @{ +*/ + + +/** @addtogroup CMSIS_CM3_NVIC CMSIS CM3 NVIC + memory mapped structure for Nested Vectored Interrupt Controller (NVIC) + @{ + */ +typedef struct +{ + __IO uint32_t ISER[8]; /*!< Offset: 0x000 Interrupt Set Enable Register */ + uint32_t RESERVED0[24]; + __IO uint32_t ICER[8]; /*!< Offset: 0x080 Interrupt Clear Enable Register */ + uint32_t RSERVED1[24]; + __IO uint32_t ISPR[8]; /*!< Offset: 0x100 Interrupt Set Pending Register */ + uint32_t RESERVED2[24]; + __IO uint32_t ICPR[8]; /*!< Offset: 0x180 Interrupt Clear Pending Register */ + uint32_t RESERVED3[24]; + __IO uint32_t IABR[8]; /*!< Offset: 0x200 Interrupt Active bit Register */ + uint32_t RESERVED4[56]; + __IO uint8_t IP[240]; /*!< Offset: 0x300 Interrupt Priority Register (8Bit wide) */ + uint32_t RESERVED5[644]; + __O uint32_t STIR; /*!< Offset: 0xE00 Software Trigger Interrupt Register */ +} NVIC_Type; +/*@}*/ /* end of group CMSIS_CM3_NVIC */ + + +/** @addtogroup CMSIS_CM3_SCB CMSIS CM3 SCB + memory mapped structure for System Control Block (SCB) + @{ + */ +typedef struct +{ + __I uint32_t CPUID; /*!< Offset: 0x00 CPU ID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x04 Interrupt Control State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x08 Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x0C Application Interrupt / Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x10 System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x14 Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x18 System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x24 System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x28 Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x2C Hard Fault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x30 Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x34 Mem Manage Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x38 Bus Fault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x3C Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x40 Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x48 Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x4C Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x50 Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x60 ISA Feature Register */ +} SCB_Type; + +/* SCB CPUID Register Definitions */ +#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */ +#define SCB_CPUID_IMPLEMENTER_Msk (0xFFul << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ + +#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */ +#define SCB_CPUID_VARIANT_Msk (0xFul << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ + +#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */ +#define SCB_CPUID_PARTNO_Msk (0xFFFul << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ + +#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */ +#define SCB_CPUID_REVISION_Msk (0xFul << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */ +#define SCB_ICSR_NMIPENDSET_Msk (1ul << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ + +#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */ +#define SCB_ICSR_PENDSVSET_Msk (1ul << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ + +#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */ +#define SCB_ICSR_PENDSVCLR_Msk (1ul << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ + +#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */ +#define SCB_ICSR_PENDSTSET_Msk (1ul << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ + +#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */ +#define SCB_ICSR_PENDSTCLR_Msk (1ul << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ + +#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */ +#define SCB_ICSR_ISRPREEMPT_Msk (1ul << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ + +#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */ +#define SCB_ICSR_ISRPENDING_Msk (1ul << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ + +#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */ +#define SCB_ICSR_VECTPENDING_Msk (0x1FFul << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ + +#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */ +#define SCB_ICSR_RETTOBASE_Msk (1ul << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ + +#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */ +#define SCB_ICSR_VECTACTIVE_Msk (0x1FFul << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */ + +/* SCB Interrupt Control State Register Definitions */ +#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */ +#define SCB_VTOR_TBLBASE_Msk (0x1FFul << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ + +#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */ +#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFul << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFul << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */ +#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFul << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ + +#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */ +#define SCB_AIRCR_ENDIANESS_Msk (1ul << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7ul << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ + +#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */ +#define SCB_AIRCR_SYSRESETREQ_Msk (1ul << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ + +#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */ +#define SCB_AIRCR_VECTCLRACTIVE_Msk (1ul << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ + +#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */ +#define SCB_AIRCR_VECTRESET_Msk (1ul << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */ + +/* SCB System Control Register Definitions */ +#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */ +#define SCB_SCR_SEVONPEND_Msk (1ul << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ + +#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */ +#define SCB_SCR_SLEEPDEEP_Msk (1ul << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ + +#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */ +#define SCB_SCR_SLEEPONEXIT_Msk (1ul << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ + +/* SCB Configuration Control Register Definitions */ +#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */ +#define SCB_CCR_STKALIGN_Msk (1ul << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ + +#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */ +#define SCB_CCR_BFHFNMIGN_Msk (1ul << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ + +#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */ +#define SCB_CCR_DIV_0_TRP_Msk (1ul << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ + +#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */ +#define SCB_CCR_UNALIGN_TRP_Msk (1ul << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ + +#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */ +#define SCB_CCR_USERSETMPEND_Msk (1ul << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ + +#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */ +#define SCB_CCR_NONBASETHRDENA_Msk (1ul << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */ + +/* SCB System Handler Control and State Register Definitions */ +#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */ +#define SCB_SHCSR_USGFAULTENA_Msk (1ul << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ + +#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */ +#define SCB_SHCSR_BUSFAULTENA_Msk (1ul << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ + +#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */ +#define SCB_SHCSR_MEMFAULTENA_Msk (1ul << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ + +#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */ +#define SCB_SHCSR_SVCALLPENDED_Msk (1ul << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ + +#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */ +#define SCB_SHCSR_BUSFAULTPENDED_Msk (1ul << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ + +#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */ +#define SCB_SHCSR_MEMFAULTPENDED_Msk (1ul << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ + +#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */ +#define SCB_SHCSR_USGFAULTPENDED_Msk (1ul << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ + +#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */ +#define SCB_SHCSR_SYSTICKACT_Msk (1ul << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ + +#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */ +#define SCB_SHCSR_PENDSVACT_Msk (1ul << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ + +#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */ +#define SCB_SHCSR_MONITORACT_Msk (1ul << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ + +#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */ +#define SCB_SHCSR_SVCALLACT_Msk (1ul << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ + +#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */ +#define SCB_SHCSR_USGFAULTACT_Msk (1ul << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ + +#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */ +#define SCB_SHCSR_BUSFAULTACT_Msk (1ul << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ + +#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */ +#define SCB_SHCSR_MEMFAULTACT_Msk (1ul << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */ + +/* SCB Configurable Fault Status Registers Definitions */ +#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */ +#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFul << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ + +#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */ +#define SCB_CFSR_BUSFAULTSR_Msk (0xFFul << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ + +#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */ +#define SCB_CFSR_MEMFAULTSR_Msk (0xFFul << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ + +/* SCB Hard Fault Status Registers Definitions */ +#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */ +#define SCB_HFSR_DEBUGEVT_Msk (1ul << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ + +#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */ +#define SCB_HFSR_FORCED_Msk (1ul << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ + +#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */ +#define SCB_HFSR_VECTTBL_Msk (1ul << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ + +/* SCB Debug Fault Status Register Definitions */ +#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */ +#define SCB_DFSR_EXTERNAL_Msk (1ul << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ + +#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */ +#define SCB_DFSR_VCATCH_Msk (1ul << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ + +#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */ +#define SCB_DFSR_DWTTRAP_Msk (1ul << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ + +#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */ +#define SCB_DFSR_BKPT_Msk (1ul << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ + +#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */ +#define SCB_DFSR_HALTED_Msk (1ul << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */ +/*@}*/ /* end of group CMSIS_CM3_SCB */ + + +/** @addtogroup CMSIS_CM3_SysTick CMSIS CM3 SysTick + memory mapped structure for SysTick + @{ + */ +typedef struct +{ + __IO uint32_t CTRL; /*!< Offset: 0x00 SysTick Control and Status Register */ + __IO uint32_t LOAD; /*!< Offset: 0x04 SysTick Reload Value Register */ + __IO uint32_t VAL; /*!< Offset: 0x08 SysTick Current Value Register */ + __I uint32_t CALIB; /*!< Offset: 0x0C SysTick Calibration Register */ +} SysTick_Type; + +/* SysTick Control / Status Register Definitions */ +#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */ +#define SysTick_CTRL_COUNTFLAG_Msk (1ul << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ + +#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */ +#define SysTick_CTRL_CLKSOURCE_Msk (1ul << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ + +#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */ +#define SysTick_CTRL_TICKINT_Msk (1ul << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ + +#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */ +#define SysTick_CTRL_ENABLE_Msk (1ul << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */ + +/* SysTick Reload Register Definitions */ +#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */ +#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFul << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */ + +/* SysTick Current Register Definitions */ +#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */ +#define SysTick_VAL_CURRENT_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */ + +/* SysTick Calibration Register Definitions */ +#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */ +#define SysTick_CALIB_NOREF_Msk (1ul << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ + +#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */ +#define SysTick_CALIB_SKEW_Msk (1ul << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ + +#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */ +#define SysTick_CALIB_TENMS_Msk (0xFFFFFFul << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */ +/*@}*/ /* end of group CMSIS_CM3_SysTick */ + + +/** @addtogroup CMSIS_CM3_ITM CMSIS CM3 ITM + memory mapped structure for Instrumentation Trace Macrocell (ITM) + @{ + */ +typedef struct +{ + __O union + { + __O uint8_t u8; /*!< Offset: ITM Stimulus Port 8-bit */ + __O uint16_t u16; /*!< Offset: ITM Stimulus Port 16-bit */ + __O uint32_t u32; /*!< Offset: ITM Stimulus Port 32-bit */ + } PORT [32]; /*!< Offset: 0x00 ITM Stimulus Port Registers */ + uint32_t RESERVED0[864]; + __IO uint32_t TER; /*!< Offset: ITM Trace Enable Register */ + uint32_t RESERVED1[15]; + __IO uint32_t TPR; /*!< Offset: ITM Trace Privilege Register */ + uint32_t RESERVED2[15]; + __IO uint32_t TCR; /*!< Offset: ITM Trace Control Register */ + uint32_t RESERVED3[29]; + __IO uint32_t IWR; /*!< Offset: ITM Integration Write Register */ + __IO uint32_t IRR; /*!< Offset: ITM Integration Read Register */ + __IO uint32_t IMCR; /*!< Offset: ITM Integration Mode Control Register */ + uint32_t RESERVED4[43]; + __IO uint32_t LAR; /*!< Offset: ITM Lock Access Register */ + __IO uint32_t LSR; /*!< Offset: ITM Lock Status Register */ + uint32_t RESERVED5[6]; + __I uint32_t PID4; /*!< Offset: ITM Peripheral Identification Register #4 */ + __I uint32_t PID5; /*!< Offset: ITM Peripheral Identification Register #5 */ + __I uint32_t PID6; /*!< Offset: ITM Peripheral Identification Register #6 */ + __I uint32_t PID7; /*!< Offset: ITM Peripheral Identification Register #7 */ + __I uint32_t PID0; /*!< Offset: ITM Peripheral Identification Register #0 */ + __I uint32_t PID1; /*!< Offset: ITM Peripheral Identification Register #1 */ + __I uint32_t PID2; /*!< Offset: ITM Peripheral Identification Register #2 */ + __I uint32_t PID3; /*!< Offset: ITM Peripheral Identification Register #3 */ + __I uint32_t CID0; /*!< Offset: ITM Component Identification Register #0 */ + __I uint32_t CID1; /*!< Offset: ITM Component Identification Register #1 */ + __I uint32_t CID2; /*!< Offset: ITM Component Identification Register #2 */ + __I uint32_t CID3; /*!< Offset: ITM Component Identification Register #3 */ +} ITM_Type; + +/* ITM Trace Privilege Register Definitions */ +#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */ +#define ITM_TPR_PRIVMASK_Msk (0xFul << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */ + +/* ITM Trace Control Register Definitions */ +#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */ +#define ITM_TCR_BUSY_Msk (1ul << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ + +#define ITM_TCR_ATBID_Pos 16 /*!< ITM TCR: ATBID Position */ +#define ITM_TCR_ATBID_Msk (0x7Ful << ITM_TCR_ATBID_Pos) /*!< ITM TCR: ATBID Mask */ + +#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */ +#define ITM_TCR_TSPrescale_Msk (3ul << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ + +#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */ +#define ITM_TCR_SWOENA_Msk (1ul << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ + +#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */ +#define ITM_TCR_DWTENA_Msk (1ul << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ + +#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */ +#define ITM_TCR_SYNCENA_Msk (1ul << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ + +#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */ +#define ITM_TCR_TSENA_Msk (1ul << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ + +#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */ +#define ITM_TCR_ITMENA_Msk (1ul << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */ + +/* ITM Integration Write Register Definitions */ +#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */ +#define ITM_IWR_ATVALIDM_Msk (1ul << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */ + +/* ITM Integration Read Register Definitions */ +#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */ +#define ITM_IRR_ATREADYM_Msk (1ul << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */ + +/* ITM Integration Mode Control Register Definitions */ +#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */ +#define ITM_IMCR_INTEGRATION_Msk (1ul << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */ + +/* ITM Lock Status Register Definitions */ +#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */ +#define ITM_LSR_ByteAcc_Msk (1ul << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ + +#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */ +#define ITM_LSR_Access_Msk (1ul << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ + +#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */ +#define ITM_LSR_Present_Msk (1ul << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */ +/*@}*/ /* end of group CMSIS_CM3_ITM */ + + +/** @addtogroup CMSIS_CM3_InterruptType CMSIS CM3 Interrupt Type + memory mapped structure for Interrupt Type + @{ + */ +typedef struct +{ + uint32_t RESERVED0; + __I uint32_t ICTR; /*!< Offset: 0x04 Interrupt Control Type Register */ +#if ((defined __CM3_REV) && (__CM3_REV >= 0x200)) + __IO uint32_t ACTLR; /*!< Offset: 0x08 Auxiliary Control Register */ +#else + uint32_t RESERVED1; +#endif +} InterruptType_Type; + +/* Interrupt Controller Type Register Definitions */ +#define InterruptType_ICTR_INTLINESNUM_Pos 0 /*!< InterruptType ICTR: INTLINESNUM Position */ +#define InterruptType_ICTR_INTLINESNUM_Msk (0x1Ful << InterruptType_ICTR_INTLINESNUM_Pos) /*!< InterruptType ICTR: INTLINESNUM Mask */ + +/* Auxiliary Control Register Definitions */ +#define InterruptType_ACTLR_DISFOLD_Pos 2 /*!< InterruptType ACTLR: DISFOLD Position */ +#define InterruptType_ACTLR_DISFOLD_Msk (1ul << InterruptType_ACTLR_DISFOLD_Pos) /*!< InterruptType ACTLR: DISFOLD Mask */ + +#define InterruptType_ACTLR_DISDEFWBUF_Pos 1 /*!< InterruptType ACTLR: DISDEFWBUF Position */ +#define InterruptType_ACTLR_DISDEFWBUF_Msk (1ul << InterruptType_ACTLR_DISDEFWBUF_Pos) /*!< InterruptType ACTLR: DISDEFWBUF Mask */ + +#define InterruptType_ACTLR_DISMCYCINT_Pos 0 /*!< InterruptType ACTLR: DISMCYCINT Position */ +#define InterruptType_ACTLR_DISMCYCINT_Msk (1ul << InterruptType_ACTLR_DISMCYCINT_Pos) /*!< InterruptType ACTLR: DISMCYCINT Mask */ +/*@}*/ /* end of group CMSIS_CM3_InterruptType */ + + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) +/** @addtogroup CMSIS_CM3_MPU CMSIS CM3 MPU + memory mapped structure for Memory Protection Unit (MPU) + @{ + */ +typedef struct +{ + __I uint32_t TYPE; /*!< Offset: 0x00 MPU Type Register */ + __IO uint32_t CTRL; /*!< Offset: 0x04 MPU Control Register */ + __IO uint32_t RNR; /*!< Offset: 0x08 MPU Region RNRber Register */ + __IO uint32_t RBAR; /*!< Offset: 0x0C MPU Region Base Address Register */ + __IO uint32_t RASR; /*!< Offset: 0x10 MPU Region Attribute and Size Register */ + __IO uint32_t RBAR_A1; /*!< Offset: 0x14 MPU Alias 1 Region Base Address Register */ + __IO uint32_t RASR_A1; /*!< Offset: 0x18 MPU Alias 1 Region Attribute and Size Register */ + __IO uint32_t RBAR_A2; /*!< Offset: 0x1C MPU Alias 2 Region Base Address Register */ + __IO uint32_t RASR_A2; /*!< Offset: 0x20 MPU Alias 2 Region Attribute and Size Register */ + __IO uint32_t RBAR_A3; /*!< Offset: 0x24 MPU Alias 3 Region Base Address Register */ + __IO uint32_t RASR_A3; /*!< Offset: 0x28 MPU Alias 3 Region Attribute and Size Register */ +} MPU_Type; + +/* MPU Type Register */ +#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */ +#define MPU_TYPE_IREGION_Msk (0xFFul << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ + +#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */ +#define MPU_TYPE_DREGION_Msk (0xFFul << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ + +#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */ +#define MPU_TYPE_SEPARATE_Msk (1ul << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */ + +/* MPU Control Register */ +#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */ +#define MPU_CTRL_PRIVDEFENA_Msk (1ul << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ + +#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */ +#define MPU_CTRL_HFNMIENA_Msk (1ul << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ + +#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */ +#define MPU_CTRL_ENABLE_Msk (1ul << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */ + +/* MPU Region Number Register */ +#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */ +#define MPU_RNR_REGION_Msk (0xFFul << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */ + +/* MPU Region Base Address Register */ +#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */ +#define MPU_RBAR_ADDR_Msk (0x7FFFFFFul << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ + +#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */ +#define MPU_RBAR_VALID_Msk (1ul << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ + +#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */ +#define MPU_RBAR_REGION_Msk (0xFul << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */ + +/* MPU Region Attribute and Size Register */ +#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: XN Position */ +#define MPU_RASR_XN_Msk (1ul << MPU_RASR_XN_Pos) /*!< MPU RASR: XN Mask */ + +#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: AP Position */ +#define MPU_RASR_AP_Msk (7ul << MPU_RASR_AP_Pos) /*!< MPU RASR: AP Mask */ + +#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: TEX Position */ +#define MPU_RASR_TEX_Msk (7ul << MPU_RASR_TEX_Pos) /*!< MPU RASR: TEX Mask */ + +#define MPU_RASR_S_Pos 18 /*!< MPU RASR: Shareable bit Position */ +#define MPU_RASR_S_Msk (1ul << MPU_RASR_S_Pos) /*!< MPU RASR: Shareable bit Mask */ + +#define MPU_RASR_C_Pos 17 /*!< MPU RASR: Cacheable bit Position */ +#define MPU_RASR_C_Msk (1ul << MPU_RASR_C_Pos) /*!< MPU RASR: Cacheable bit Mask */ + +#define MPU_RASR_B_Pos 16 /*!< MPU RASR: Bufferable bit Position */ +#define MPU_RASR_B_Msk (1ul << MPU_RASR_B_Pos) /*!< MPU RASR: Bufferable bit Mask */ + +#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */ +#define MPU_RASR_SRD_Msk (0xFFul << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ + +#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */ +#define MPU_RASR_SIZE_Msk (0x1Ful << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ + +#define MPU_RASR_ENA_Pos 0 /*!< MPU RASR: Region enable bit Position */ +#define MPU_RASR_ENA_Msk (0x1Ful << MPU_RASR_ENA_Pos) /*!< MPU RASR: Region enable bit Disable Mask */ + +/*@}*/ /* end of group CMSIS_CM3_MPU */ +#endif + + +/** @addtogroup CMSIS_CM3_CoreDebug CMSIS CM3 Core Debug + memory mapped structure for Core Debug Register + @{ + */ +typedef struct +{ + __IO uint32_t DHCSR; /*!< Offset: 0x00 Debug Halting Control and Status Register */ + __O uint32_t DCRSR; /*!< Offset: 0x04 Debug Core Register Selector Register */ + __IO uint32_t DCRDR; /*!< Offset: 0x08 Debug Core Register Data Register */ + __IO uint32_t DEMCR; /*!< Offset: 0x0C Debug Exception and Monitor Control Register */ +} CoreDebug_Type; + +/* Debug Halting Control and Status Register */ +#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */ +#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFul << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ + +#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */ +#define CoreDebug_DHCSR_S_RESET_ST_Msk (1ul << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ + +#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ +#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1ul << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ + +#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */ +#define CoreDebug_DHCSR_S_LOCKUP_Msk (1ul << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ + +#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */ +#define CoreDebug_DHCSR_S_SLEEP_Msk (1ul << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ + +#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */ +#define CoreDebug_DHCSR_S_HALT_Msk (1ul << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ + +#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */ +#define CoreDebug_DHCSR_S_REGRDY_Msk (1ul << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ + +#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ +#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1ul << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ + +#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */ +#define CoreDebug_DHCSR_C_MASKINTS_Msk (1ul << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ + +#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */ +#define CoreDebug_DHCSR_C_STEP_Msk (1ul << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ + +#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */ +#define CoreDebug_DHCSR_C_HALT_Msk (1ul << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ + +#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */ +#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1ul << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ + +/* Debug Core Register Selector Register */ +#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */ +#define CoreDebug_DCRSR_REGWnR_Msk (1ul << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ + +#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */ +#define CoreDebug_DCRSR_REGSEL_Msk (0x1Ful << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */ + +/* Debug Exception and Monitor Control Register */ +#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */ +#define CoreDebug_DEMCR_TRCENA_Msk (1ul << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ + +#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */ +#define CoreDebug_DEMCR_MON_REQ_Msk (1ul << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ + +#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */ +#define CoreDebug_DEMCR_MON_STEP_Msk (1ul << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ + +#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */ +#define CoreDebug_DEMCR_MON_PEND_Msk (1ul << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ + +#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */ +#define CoreDebug_DEMCR_MON_EN_Msk (1ul << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ + +#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */ +#define CoreDebug_DEMCR_VC_HARDERR_Msk (1ul << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ + +#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */ +#define CoreDebug_DEMCR_VC_INTERR_Msk (1ul << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ + +#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */ +#define CoreDebug_DEMCR_VC_BUSERR_Msk (1ul << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ + +#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */ +#define CoreDebug_DEMCR_VC_STATERR_Msk (1ul << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ + +#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */ +#define CoreDebug_DEMCR_VC_CHKERR_Msk (1ul << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ + +#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */ +#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1ul << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ + +#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */ +#define CoreDebug_DEMCR_VC_MMERR_Msk (1ul << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ + +#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */ +#define CoreDebug_DEMCR_VC_CORERESET_Msk (1ul << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ +/*@}*/ /* end of group CMSIS_CM3_CoreDebug */ + + +/* Memory mapping of Cortex-M3 Hardware */ +#define SCS_BASE (0xE000E000) /*!< System Control Space Base Address */ +#define ITM_BASE (0xE0000000) /*!< ITM Base Address */ +#define CoreDebug_BASE (0xE000EDF0) /*!< Core Debug Base Address */ +#define SysTick_BASE (SCS_BASE + 0x0010) /*!< SysTick Base Address */ +#define NVIC_BASE (SCS_BASE + 0x0100) /*!< NVIC Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00) /*!< System Control Block Base Address */ + +#define InterruptType ((InterruptType_Type *) SCS_BASE) /*!< Interrupt Type Register */ +#define SCB ((SCB_Type *) SCB_BASE) /*!< SCB configuration struct */ +#define SysTick ((SysTick_Type *) SysTick_BASE) /*!< SysTick configuration struct */ +#define NVIC ((NVIC_Type *) NVIC_BASE) /*!< NVIC configuration struct */ +#define ITM ((ITM_Type *) ITM_BASE) /*!< ITM configuration struct */ +#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ + +#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1) + #define MPU_BASE (SCS_BASE + 0x0D90) /*!< Memory Protection Unit */ + #define MPU ((MPU_Type*) MPU_BASE) /*!< Memory Protection Unit */ +#endif + +/*@}*/ /* end of group CMSIS_CM3_core_register */ + + +/******************************************************************************* + * Hardware Abstraction Layer + ******************************************************************************/ + +#if defined ( __CC_ARM ) + #define __ASM __asm /*!< asm keyword for ARM Compiler */ + #define __INLINE __inline /*!< inline keyword for ARM Compiler */ + +#elif defined ( __ICCARM__ ) + #define __ASM __asm /*!< asm keyword for IAR Compiler */ + #define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */ + +#elif defined ( __GNUC__ ) + #define __ASM __asm /*!< asm keyword for GNU Compiler */ + #define __INLINE inline /*!< inline keyword for GNU Compiler */ + +#elif defined ( __TASKING__ ) + #define __ASM __asm /*!< asm keyword for TASKING Compiler */ + #define __INLINE inline /*!< inline keyword for TASKING Compiler */ + +#endif + + +/* ################### Compiler specific Intrinsics ########################### */ + +#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/ +/* ARM armcc specific functions */ + +#define __enable_fault_irq __enable_fiq +#define __disable_fault_irq __disable_fiq + +#define __NOP __nop +#define __WFI __wfi +#define __WFE __wfe +#define __SEV __sev +#define __ISB() __isb(0) +#define __DSB() __dsb(0) +#define __DMB() __dmb(0) +#define __REV __rev +#define __RBIT __rbit +#define __LDREXB(ptr) ((unsigned char ) __ldrex(ptr)) +#define __LDREXH(ptr) ((unsigned short) __ldrex(ptr)) +#define __LDREXW(ptr) ((unsigned int ) __ldrex(ptr)) +#define __STREXB(value, ptr) __strex(value, ptr) +#define __STREXH(value, ptr) __strex(value, ptr) +#define __STREXW(value, ptr) __strex(value, ptr) + + +/* intrinsic unsigned long long __ldrexd(volatile void *ptr) */ +/* intrinsic int __strexd(unsigned long long val, volatile void *ptr) */ +/* intrinsic void __enable_irq(); */ +/* intrinsic void __disable_irq(); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + + +#if (__ARMCC_VERSION < 400000) + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +extern void __CLREX(void); + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +#else /* (__ARMCC_VERSION >= 400000) */ + +/** + * @brief Remove the exclusive lock created by ldrex + * + * Removes the exclusive lock which is created by ldrex. + */ +#define __CLREX __clrex + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +static __INLINE uint32_t __get_BASEPRI(void) +{ + register uint32_t __regBasePri __ASM("basepri"); + return(__regBasePri); +} + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +static __INLINE void __set_BASEPRI(uint32_t basePri) +{ + register uint32_t __regBasePri __ASM("basepri"); + __regBasePri = (basePri & 0xff); +} + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +static __INLINE uint32_t __get_PRIMASK(void) +{ + register uint32_t __regPriMask __ASM("primask"); + return(__regPriMask); +} + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +static __INLINE void __set_PRIMASK(uint32_t priMask) +{ + register uint32_t __regPriMask __ASM("primask"); + __regPriMask = (priMask); +} + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +static __INLINE uint32_t __get_FAULTMASK(void) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + return(__regFaultMask); +} + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +static __INLINE void __set_FAULTMASK(uint32_t faultMask) +{ + register uint32_t __regFaultMask __ASM("faultmask"); + __regFaultMask = (faultMask & 1); +} + +/** + * @brief Return the Control Register value + * + * @return Control value + * + * Return the content of the control register + */ +static __INLINE uint32_t __get_CONTROL(void) +{ + register uint32_t __regControl __ASM("control"); + return(__regControl); +} + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +static __INLINE void __set_CONTROL(uint32_t control) +{ + register uint32_t __regControl __ASM("control"); + __regControl = control; +} + +#endif /* __ARMCC_VERSION */ + + + +#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/ +/* IAR iccarm specific functions */ + +#define __enable_irq __enable_interrupt /*!< global Interrupt enable */ +#define __disable_irq __disable_interrupt /*!< global Interrupt disable */ + +static __INLINE void __enable_fault_irq() { __ASM ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM ("cpsid f"); } + +#define __NOP __no_operation /*!< no operation intrinsic in IAR Compiler */ +static __INLINE void __WFI() { __ASM ("wfi"); } +static __INLINE void __WFE() { __ASM ("wfe"); } +static __INLINE void __SEV() { __ASM ("sev"); } +static __INLINE void __CLREX() { __ASM ("clrex"); } + +/* intrinsic void __ISB(void) */ +/* intrinsic void __DSB(void) */ +/* intrinsic void __DMB(void) */ +/* intrinsic void __set_PRIMASK(); */ +/* intrinsic void __get_PRIMASK(); */ +/* intrinsic void __set_FAULTMASK(); */ +/* intrinsic void __get_FAULTMASK(); */ +/* intrinsic uint32_t __REV(uint32_t value); */ +/* intrinsic uint32_t __REVSH(uint32_t value); */ +/* intrinsic unsigned long __STREX(unsigned long, unsigned long); */ +/* intrinsic unsigned long __LDREX(unsigned long *); */ + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit values) + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + + +#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/ +/* GNU gcc specific functions */ + +static __INLINE void __enable_irq() { __ASM volatile ("cpsie i"); } +static __INLINE void __disable_irq() { __ASM volatile ("cpsid i"); } + +static __INLINE void __enable_fault_irq() { __ASM volatile ("cpsie f"); } +static __INLINE void __disable_fault_irq() { __ASM volatile ("cpsid f"); } + +static __INLINE void __NOP() { __ASM volatile ("nop"); } +static __INLINE void __WFI() { __ASM volatile ("wfi"); } +static __INLINE void __WFE() { __ASM volatile ("wfe"); } +static __INLINE void __SEV() { __ASM volatile ("sev"); } +static __INLINE void __ISB() { __ASM volatile ("isb"); } +static __INLINE void __DSB() { __ASM volatile ("dsb"); } +static __INLINE void __DMB() { __ASM volatile ("dmb"); } +static __INLINE void __CLREX() { __ASM volatile ("clrex"); } + + +/** + * @brief Return the Process Stack Pointer + * + * @return ProcessStackPointer + * + * Return the actual process stack pointer + */ +extern uint32_t __get_PSP(void); + +/** + * @brief Set the Process Stack Pointer + * + * @param topOfProcStack Process Stack Pointer + * + * Assign the value ProcessStackPointer to the MSP + * (process stack pointer) Cortex processor register + */ +extern void __set_PSP(uint32_t topOfProcStack); + +/** + * @brief Return the Main Stack Pointer + * + * @return Main Stack Pointer + * + * Return the current value of the MSP (main stack pointer) + * Cortex processor register + */ +extern uint32_t __get_MSP(void); + +/** + * @brief Set the Main Stack Pointer + * + * @param topOfMainStack Main Stack Pointer + * + * Assign the value mainStackPointer to the MSP + * (main stack pointer) Cortex processor register + */ +extern void __set_MSP(uint32_t topOfMainStack); + +/** + * @brief Return the Base Priority value + * + * @return BasePriority + * + * Return the content of the base priority register + */ +extern uint32_t __get_BASEPRI(void); + +/** + * @brief Set the Base Priority value + * + * @param basePri BasePriority + * + * Set the base priority register + */ +extern void __set_BASEPRI(uint32_t basePri); + +/** + * @brief Return the Priority Mask value + * + * @return PriMask + * + * Return state of the priority mask bit from the priority mask register + */ +extern uint32_t __get_PRIMASK(void); + +/** + * @brief Set the Priority Mask value + * + * @param priMask PriMask + * + * Set the priority mask bit in the priority mask register + */ +extern void __set_PRIMASK(uint32_t priMask); + +/** + * @brief Return the Fault Mask value + * + * @return FaultMask + * + * Return the content of the fault mask register + */ +extern uint32_t __get_FAULTMASK(void); + +/** + * @brief Set the Fault Mask value + * + * @param faultMask faultMask value + * + * Set the fault mask register + */ +extern void __set_FAULTMASK(uint32_t faultMask); + +/** + * @brief Return the Control Register value +* +* @return Control value + * + * Return the content of the control register + */ +extern uint32_t __get_CONTROL(void); + +/** + * @brief Set the Control Register value + * + * @param control Control value + * + * Set the control register + */ +extern void __set_CONTROL(uint32_t control); + +/** + * @brief Reverse byte order in integer value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in integer value + */ +extern uint32_t __REV(uint32_t value); + +/** + * @brief Reverse byte order in unsigned short value + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in unsigned short value + */ +extern uint32_t __REV16(uint16_t value); + +/** + * @brief Reverse byte order in signed short value with sign extension to integer + * + * @param value value to reverse + * @return reversed value + * + * Reverse byte order in signed short value with sign extension to integer + */ +extern int32_t __REVSH(int16_t value); + +/** + * @brief Reverse bit order of value + * + * @param value value to reverse + * @return reversed value + * + * Reverse bit order of value + */ +extern uint32_t __RBIT(uint32_t value); + +/** + * @brief LDR Exclusive (8 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 8 bit value + */ +extern uint8_t __LDREXB(uint8_t *addr); + +/** + * @brief LDR Exclusive (16 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 16 bit values + */ +extern uint16_t __LDREXH(uint16_t *addr); + +/** + * @brief LDR Exclusive (32 bit) + * + * @param *addr address pointer + * @return value of (*address) + * + * Exclusive LDR command for 32 bit values + */ +extern uint32_t __LDREXW(uint32_t *addr); + +/** + * @brief STR Exclusive (8 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 8 bit values + */ +extern uint32_t __STREXB(uint8_t value, uint8_t *addr); + +/** + * @brief STR Exclusive (16 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 16 bit values + */ +extern uint32_t __STREXH(uint16_t value, uint16_t *addr); + +/** + * @brief STR Exclusive (32 bit) + * + * @param value value to store + * @param *addr address pointer + * @return successful / failed + * + * Exclusive STR command for 32 bit values + */ +extern uint32_t __STREXW(uint32_t value, uint32_t *addr); + + +#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/ +/* TASKING carm specific functions */ + +/* + * The CMSIS functions have been implemented as intrinsics in the compiler. + * Please use "carm -?i" to get an up to date list of all instrinsics, + * Including the CMSIS ones. + */ + +#endif + + +/** @addtogroup CMSIS_CM3_Core_FunctionInterface CMSIS CM3 Core Function Interface + Core Function Interface containing: + - Core NVIC Functions + - Core SysTick Functions + - Core Reset Functions +*/ +/*@{*/ + +/* ########################## NVIC functions #################################### */ + +/** + * @brief Set the Priority Grouping in NVIC Interrupt Controller + * + * @param PriorityGroup is priority grouping field + * + * Set the priority grouping field using the required unlock sequence. + * The parameter priority_grouping is assigned to the field + * SCB->AIRCR [10:8] PRIGROUP field. Only values from 0..7 are used. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. + */ +static __INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) +{ + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + + reg_value = SCB->AIRCR; /* read old register configuration */ + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */ + reg_value = (reg_value | + (0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); /* Insert write key and priorty group */ + SCB->AIRCR = reg_value; +} + +/** + * @brief Get the Priority Grouping from NVIC Interrupt Controller + * + * @return priority grouping field + * + * Get the priority grouping from NVIC Interrupt Controller. + * priority grouping is SCB->AIRCR [10:8] PRIGROUP field. + */ +static __INLINE uint32_t NVIC_GetPriorityGrouping(void) +{ + return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */ +} + +/** + * @brief Enable Interrupt in NVIC Interrupt Controller + * + * @param IRQn The positive number of the external interrupt to enable + * + * Enable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_EnableIRQ(IRQn_Type IRQn) +{ + NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */ +} + +/** + * @brief Disable the interrupt line for external interrupt specified + * + * @param IRQn The positive number of the external interrupt to disable + * + * Disable a device specific interupt in the NVIC interrupt controller. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_DisableIRQ(IRQn_Type IRQn) +{ + NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */ +} + +/** + * @brief Read the interrupt pending bit for a device specific interrupt source + * + * @param IRQn The number of the device specifc interrupt + * @return 1 = interrupt pending, 0 = interrupt not pending + * + * Read the pending register in NVIC and return 1 if its status is pending, + * otherwise it returns 0 + */ +static __INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn) +{ + return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */ +} + +/** + * @brief Set the pending bit for an external interrupt + * + * @param IRQn The number of the interrupt for set pending + * + * Set the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */ +} + +/** + * @brief Clear the pending bit for an external interrupt + * + * @param IRQn The number of the interrupt for clear pending + * + * Clear the pending bit for the specified interrupt. + * The interrupt number cannot be a negative value. + */ +static __INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn) +{ + NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */ +} + +/** + * @brief Read the active bit for an external interrupt + * + * @param IRQn The number of the interrupt for read active bit + * @return 1 = interrupt active, 0 = interrupt not active + * + * Read the active register in NVIC and returns 1 if its status is active, + * otherwise it returns 0. + */ +static __INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn) +{ + return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */ +} + +/** + * @brief Set the priority for an interrupt + * + * @param IRQn The number of the interrupt for set priority + * @param priority The priority to set + * + * Set the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) +{ + if(IRQn < 0) { + SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M3 System Interrupts */ + else { + NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */ +} + +/** + * @brief Read the priority for an interrupt + * + * @param IRQn The number of the interrupt for get priority + * @return The priority for the interrupt + * + * Read the priority for the specified interrupt. The interrupt + * number can be positive to specify an external (device specific) + * interrupt, or negative to specify an internal (core) interrupt. + * + * The returned priority value is automatically aligned to the implemented + * priority bits of the microcontroller. + * + * Note: The priority cannot be set for every core interrupt. + */ +static __INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn) +{ + + if(IRQn < 0) { + return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M3 system interrupts */ + else { + return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */ +} + + +/** + * @brief Encode the priority for an interrupt + * + * @param PriorityGroup The used priority group + * @param PreemptPriority The preemptive priority value (starting from 0) + * @param SubPriority The sub priority value (starting from 0) + * @return The encoded priority for the interrupt + * + * Encode the priority for an interrupt with the given priority group, + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The returned priority value can be used for NVIC_SetPriority(...) function + */ +static __INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + return ( + ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) | + ((SubPriority & ((1 << (SubPriorityBits )) - 1))) + ); +} + + +/** + * @brief Decode the priority of an interrupt + * + * @param Priority The priority for the interrupt + * @param PriorityGroup The used priority group + * @param pPreemptPriority The preemptive priority value (starting from 0) + * @param pSubPriority The sub priority value (starting from 0) + * + * Decode an interrupt priority value with the given priority group to + * preemptive priority value and sub priority value. + * In case of a conflict between priority grouping and available + * priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set. + * + * The priority value can be retrieved with NVIC_GetPriority(...) function + */ +static __INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority) +{ + uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */ + uint32_t PreemptPriorityBits; + uint32_t SubPriorityBits; + + PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp; + SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS; + + *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1); + *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1); +} + + + +/* ################################## SysTick function ############################################ */ + +#if (!defined (__Vendor_SysTickConfig)) || (__Vendor_SysTickConfig == 0) + +/** + * @brief Initialize and start the SysTick counter and its interrupt. + * + * @param ticks number of ticks between two interrupts + * @return 1 = failed, 0 = successful + * + * Initialise the system tick timer and its interrupt and start the + * system tick timer / counter in free running mode to generate + * periodical interrupts. + */ +static __INLINE uint32_t SysTick_Config(uint32_t ticks) +{ + if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + + SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Cortex-M0 System Interrupts */ + SysTick->VAL = 0; /* Load the SysTick Counter Value */ + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | + SysTick_CTRL_TICKINT_Msk | + SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ + return (0); /* Function successful */ +} + +#endif + + + + +/* ################################## Reset function ############################################ */ + +/** + * @brief Initiate a system reset request. + * + * Initiate a system reset request to reset the MCU + */ +static __INLINE void NVIC_SystemReset(void) +{ + SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | + SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */ + __DSB(); /* Ensure completion of memory access */ + while(1); /* wait until reset */ +} + +/*@}*/ /* end of group CMSIS_CM3_Core_FunctionInterface */ + + + +/* ##################################### Debug In/Output function ########################################### */ + +/** @addtogroup CMSIS_CM3_CoreDebugInterface CMSIS CM3 Core Debug Interface + Core Debug Interface containing: + - Core Debug Receive / Transmit Functions + - Core Debug Defines + - Core Debug Variables +*/ +/*@{*/ + +extern volatile int ITM_RxBuffer; /*!< variable to receive characters */ +#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< value identifying ITM_RxBuffer is ready for next character */ + + +/** + * @brief Outputs a character via the ITM channel 0 + * + * @param ch character to output + * @return character to output + * + * The function outputs a character via the ITM channel 0. + * The function returns when no debugger is connected that has booked the output. + * It is blocking when a debugger is connected, but the previous character send is not transmitted. + */ +static __INLINE uint32_t ITM_SendChar (uint32_t ch) +{ + if ((CoreDebug->DEMCR & CoreDebug_DEMCR_TRCENA_Msk) && /* Trace enabled */ + (ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */ + (ITM->TER & (1ul << 0) ) ) /* ITM Port #0 enabled */ + { + while (ITM->PORT[0].u32 == 0); + ITM->PORT[0].u8 = (uint8_t) ch; + } + return (ch); +} + + +/** + * @brief Inputs a character via variable ITM_RxBuffer + * + * @return received character, -1 = no character received + * + * The function inputs a character via variable ITM_RxBuffer. + * The function returns when no debugger is connected that has booked the output. + * It is blocking when a debugger is connected, but the previous character send is not transmitted. + */ +static __INLINE int ITM_ReceiveChar (void) { + int ch = -1; /* no character available */ + + if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) { + ch = ITM_RxBuffer; + ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ + } + + return (ch); +} + + +/** + * @brief Check if a character via variable ITM_RxBuffer is available + * + * @return 1 = character available, 0 = no character available + * + * The function checks variable ITM_RxBuffer whether a character is available or not. + * The function returns '1' if a character is available and '0' if no character is available. + */ +static __INLINE int ITM_CheckChar (void) { + + if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) { + return (0); /* no character available */ + } else { + return (1); /* character available */ + } +} + +/*@}*/ /* end of group CMSIS_CM3_core_DebugInterface */ + + +#ifdef __cplusplus +} +#endif + +/*@}*/ /* end of group CMSIS_CM3_core_definitions */ + +#endif /* __CM3_CORE_H__ */ + +/*lint -restore */ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html new file mode 100755 index 0000000000..b80f38df1c --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/Release_Notes.html @@ -0,0 +1,284 @@ + + + + + + + + + + + + +Release Notes for STM32F10x CMSIS + + + + + +
+


+

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

Release +Notes for STM32F10x CMSIS

+

Copyright 2011 STMicroelectronics

+

+
+

 

+ + + + + + +
+

Contents

+
    +
  1. STM32F10x CMSIS +update History
  2. +
  3. License
  4. +
+ +

STM32F10x CMSIS +update History


+

V3.5.0 / 11-March-2011

+

Main +Changes

+ +
    +
  • stm32f10x.h +and startup_stm32f10x_hd_vl.s files: remove the FSMC interrupt +definition for STM32F10x High-density Value line devices.
    +
  • +
  • system_stm32f10x.c file provided within the CMSIS folder.
    +
  • + +
+ +

3.4.0 +- 10/15/2010

+ +
    +
  1. General
  2. +
+ +
    +
  • Add support +for STM32F10x High-density Value line devices.
  • +
+
    +
  1. STM32F10x CMSIS Device Peripheral Access Layer
  2. +
+ + + +
    +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
    • Update to support High-density Value line devices
      • Add new define STM32F10X_HD_VL
      • +
      • RCC, AFIO, FSMC bits definition updated
      • +
      +
    • + + All +STM32 devices definitions are commented by default. User has to select the +appropriate device before starting else an error will be signaled on compile +time.
    • +
    • Add new IRQs definitons inside the IRQn_Type enumeration for STM23 High-density Value line devices.
    • +
    • "bool" type removed.
      +
    • +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
  • +
      +
    • "system_stm32f10x.c" moved to to "STM32F10x_StdPeriph_Template" directory. This file is also moved to each example directory under "STM32F10x_StdPeriph_Examples".
      +
    • +
    • SystemInit_ExtMemCtl() function: update to support High-density Value line devices.
    • +
    • Add "VECT_TAB_SRAM" inside "system_stm32f10x.c" +to select if the user want to place the Vector Table in internal SRAM. +An additional define is also to specify the Vector Table offset "VECT_TAB_OFFSET".
      +
    • + +
    +
  • STM32F10x CMSIS startup files:startup_stm32f10x_xx.s
    • Add three +startup files for STM32 High-density Value line devices: + startup_stm32f10x_hd_vl.s
    +
+

3.3.0 +- 04/16/2010

+ +
  1. General
+
  • Add support +for STM32F10x XL-density devices.
  • Add startup files for TrueSTUDIO toolchain
  1. STM32F10x CMSIS Device Peripheral Access Layer
+ +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
    • Update to support XL-density devices
      • Add new define STM32F10X_XL
      • Add new IRQs for TIM9..14
      • Update FLASH_TypeDef structure
      • Add new IP instances TIM9..14
      • RCC, AFIO, DBGMCU bits definition updated
    • Correct IRQs definition for MD-, LD-, MD_VL- and LD_VL-density devices (remove comma "," at the end of enum list)
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
    • SystemInit_ExtMemCtl() function: update to support XL-density devices
    • SystemInit() function: swap the order of SetSysClock() and SystemInit_ExtMemCtl() functions. 
      +
  • STM32F10x CMSIS startup files:
    • add three +startup files for STM32 XL-density devices: + startup_stm32f10x_xl.s
    • startup_stm32f10x_md_vl.s for RIDE7: add USART3 IRQ Handler (was missing in previous version)
    • Add startup files for TrueSTUDIO toolchain
+

3.2.0 +- 03/01/2010

+
    +
  1. General
  2. +
+
    + +
  • STM32F10x CMSIS files updated to CMSIS V1.30 release
  • +
  • Directory structure updated to be aligned with CMSIS V1.30
    +
  • +
  • Add support +for STM32 Low-density Value line (STM32F100x4/6) and +Medium-density Value line (STM32F100x8/B) devices
  • + +
+
    +
  1. CMSIS Core Peripheral Access Layer
+ +
    +
  1. STM32F10x CMSIS Device Peripheral Access Layer
  2. + +
+ +
    + +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer Header File: stm32f10x.h
    +
  • +
      +
    • Update +the stm32f10x.h file to support new Value line devices features: CEC +peripheral, new General purpose timers TIM15, TIM16 and TIM17.
    • +
    • Peripherals Bits definitions updated to be in line with Value line devices available features.
      +
    • +
    • HSE_Value, +HSI_Value and HSEStartup_TimeOut changed to upper case: HSE_VALUE, +HSI_VALUE and HSE_STARTUP_TIMEOUT. Old names are kept for legacy +purposes.
      +
    • +
    +
  • STM32F10x CMSIS Cortex-M3 Device Peripheral Access Layer System Files: system_stm32f10x.h and system_stm32f10x.c
    +
  • +
      +
    • SystemFrequency variable name changed to SystemCoreClock
      +
    • +
    • Default + SystemCoreClock is changed to 24MHz when Value line devices are selected and to 72MHz on other devices.
      +
    • +
    • All while(1) loop were removed from all clock setting functions. User has to handle the HSE startup failure.
      +
    • +
    • Additional function void SystemCoreClockUpdate (void) is provided.
      +
    • +
    +
  • STM32F10x CMSIS Startup files: startup_stm32f10x_xx.s
  • +
      +
    • Add new +startup files for STM32 Low-density Value line devices: + startup_stm32f10x_ld_vl.s
    • +
    • Add new startup +files for STM32 Medium-density Value line devices: + startup_stm32f10x_md_vl.s
    • +
    • SystemInit() function is called from startup file (startup_stm32f10x_xx.s) before to branch to application main.
      +To reconfigure the default setting of SystemInit() function, refer to system_stm32f10x.c file
      +
    • +
    • GNU startup file for Low density devices (startup_stm32f10x_ld.s) is updated to fix compilation errors.
      +
    • +
    + +
+ +
    +
+

License

+

The +enclosed firmware and all the related documentation are not covered by +a License Agreement, if you need such License you can contact your +local STMicroelectronics office.

+

THE +PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO +SAVE TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR +ANY DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY +CLAIMS ARISING FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY +CUSTOMERS OF THE CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH +THEIR PRODUCTS.

+

 

+
+
+

For +complete documentation on STM32(CORTEX M3) 32-Bit Microcontrollers +visit www.st.com/STM32

+
+

+
+
+

 

+
+ \ No newline at end of file diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s new file mode 100755 index 0000000000..e34a520671 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_cl.s @@ -0,0 +1,473 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_cl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Connectivity line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR + * address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss + +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word CAN1_TX_IRQHandler + .word CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word OTG_FS_WKUP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ETH_IRQHandler + .word ETH_WKUP_IRQHandler + .word CAN2_TX_IRQHandler + .word CAN2_RX0_IRQHandler + .word CAN2_RX1_IRQHandler + .word CAN2_SCE_IRQHandler + .word OTG_FS_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x Connectivity line Devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler ,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s new file mode 100755 index 0000000000..0aa91884f2 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd.s @@ -0,0 +1,469 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address, + * - Configure the clock system + * - Configure external SRAM mounted on STM3210E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s new file mode 100755 index 0000000000..55aa398616 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_hd_vl.s @@ -0,0 +1,451 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Value Line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Configure external SRAM mounted on STM32100E-EVAL board + * to be used as data memory (optional, to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word TIM12_IRQHandler + .word TIM13_IRQHandler + .word TIM14_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word DMA2_Channel5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density Value line devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM12_IRQHandler + .thumb_set TIM12_IRQHandler,Default_Handler + + .weak TIM13_IRQHandler + .thumb_set TIM13_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s new file mode 100755 index 0000000000..2c5aaa06be --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld.s @@ -0,0 +1,347 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Low Density devices.*/ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s new file mode 100755 index 0000000000..9af6e8ba0b --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_ld_vl.s @@ -0,0 +1,392 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Value Line Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s new file mode 100755 index 0000000000..c14ba21042 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md.s @@ -0,0 +1,363 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s new file mode 100755 index 0000000000..4ac1230db3 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_md_vl.s @@ -0,0 +1,408 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Value Line Devices vector table for Atollic + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s new file mode 100755 index 0000000000..19bdf5a8c9 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/TrueSTUDIO/startup_stm32f10x_xl.s @@ -0,0 +1,467 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_xl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x XL-Density Devices vector table for TrueSTUDIO toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM9_IRQHandler + .word TIM1_UP_TIM10_IRQHandler + .word TIM1_TRG_COM_TIM11_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_TIM12_IRQHandler + .word TIM8_UP_TIM13_IRQHandler + .word TIM8_TRG_COM_TIM14_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x XL-Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s new file mode 100755 index 0000000000..8196e697fd --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_cl.s @@ -0,0 +1,368 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_cl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Connectivity line devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 and ADC2 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C1 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC alarm through EXTI line + DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + DCD ETH_IRQHandler ; Ethernet + DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line + DCD CAN2_TX_IRQHandler ; CAN2 TX + DCD CAN2_RX0_IRQHandler ; CAN2 RX0 + DCD CAN2_RX1_IRQHandler ; CAN2 RX1 + DCD CAN2_SCE_IRQHandler ; CAN2 SCE + DCD OTG_FS_IRQHandler ; USB OTG FS +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT CAN1_TX_IRQHandler [WEAK] + EXPORT CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT OTG_FS_WKUP_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + EXPORT ETH_IRQHandler [WEAK] + EXPORT ETH_WKUP_IRQHandler [WEAK] + EXPORT CAN2_TX_IRQHandler [WEAK] + EXPORT CAN2_RX0_IRQHandler [WEAK] + EXPORT CAN2_RX1_IRQHandler [WEAK] + EXPORT CAN2_SCE_IRQHandler [WEAK] + EXPORT OTG_FS_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +CAN1_TX_IRQHandler +CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +OTG_FS_WKUP_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_IRQHandler +DMA2_Channel5_IRQHandler +ETH_IRQHandler +ETH_WKUP_IRQHandler +CAN2_TX_IRQHandler +CAN2_RX0_IRQHandler +CAN2_RX1_IRQHandler +CAN2_SCE_IRQHandler +OTG_FS_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s new file mode 100755 index 0000000000..adc9b94a93 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd.s @@ -0,0 +1,358 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_IRQHandler ; TIM8 Break + DCD TIM8_UP_IRQHandler ; TIM8 Update + DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger and Commutation + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + EXPORT TIM8_BRK_IRQHandler [WEAK] + EXPORT TIM8_UP_IRQHandler [WEAK] + EXPORT TIM8_TRG_COM_IRQHandler [WEAK] + EXPORT TIM8_CC_IRQHandler [WEAK] + EXPORT ADC3_IRQHandler [WEAK] + EXPORT FSMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler +TIM8_BRK_IRQHandler +TIM8_UP_IRQHandler +TIM8_TRG_COM_IRQHandler +TIM8_CC_IRQHandler +ADC3_IRQHandler +FSMC_IRQHandler +SDIO_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s new file mode 100755 index 0000000000..d6082b0961 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_hd_vl.s @@ -0,0 +1,346 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM32100E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD TIM12_IRQHandler ; TIM12 + DCD TIM13_IRQHandler ; TIM13 + DCD TIM14_IRQHandler ; TIM14 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM12_IRQHandler [WEAK] + EXPORT TIM13_IRQHandler [WEAK] + EXPORT TIM14_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + EXPORT DMA2_Channel5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM12_IRQHandler +TIM13_IRQHandler +TIM14_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler +DMA2_Channel5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s new file mode 100755 index 0000000000..3f3ac2ffd3 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld.s @@ -0,0 +1,297 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler routine +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI1_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s new file mode 100755 index 0000000000..fe22fc011b --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_ld_vl.s @@ -0,0 +1,304 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +SPI1_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s new file mode 100755 index 0000000000..f99c0c862d --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md.s @@ -0,0 +1,307 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00001000 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s new file mode 100755 index 0000000000..d3b8aa6c15 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_md_vl.s @@ -0,0 +1,315 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Value Line Devices vector table +;* for MDK-ARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM15_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM16_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM17_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT CEC_IRQHandler [WEAK] + EXPORT TIM6_DAC_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM15_IRQHandler +TIM1_UP_TIM16_IRQHandler +TIM1_TRG_COM_TIM17_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +CEC_IRQHandler +TIM6_DAC_IRQHandler +TIM7_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s new file mode 100755 index 0000000000..7970052d7c --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/arm/startup_stm32f10x_xl.s @@ -0,0 +1,358 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_xl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x XL-Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system and also configure the external +;* SRAM mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 + DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 + DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 + DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 + DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_TIM9_IRQHandler [WEAK] + EXPORT TIM1_UP_TIM10_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_TIM11_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + EXPORT TIM8_BRK_TIM12_IRQHandler [WEAK] + EXPORT TIM8_UP_TIM13_IRQHandler [WEAK] + EXPORT TIM8_TRG_COM_TIM14_IRQHandler [WEAK] + EXPORT TIM8_CC_IRQHandler [WEAK] + EXPORT ADC3_IRQHandler [WEAK] + EXPORT FSMC_IRQHandler [WEAK] + EXPORT SDIO_IRQHandler [WEAK] + EXPORT TIM5_IRQHandler [WEAK] + EXPORT SPI3_IRQHandler [WEAK] + EXPORT UART4_IRQHandler [WEAK] + EXPORT UART5_IRQHandler [WEAK] + EXPORT TIM6_IRQHandler [WEAK] + EXPORT TIM7_IRQHandler [WEAK] + EXPORT DMA2_Channel1_IRQHandler [WEAK] + EXPORT DMA2_Channel2_IRQHandler [WEAK] + EXPORT DMA2_Channel3_IRQHandler [WEAK] + EXPORT DMA2_Channel4_5_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_TIM9_IRQHandler +TIM1_UP_TIM10_IRQHandler +TIM1_TRG_COM_TIM11_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler +TIM8_BRK_TIM12_IRQHandler +TIM8_UP_TIM13_IRQHandler +TIM8_TRG_COM_TIM14_IRQHandler +TIM8_CC_IRQHandler +ADC3_IRQHandler +FSMC_IRQHandler +SDIO_IRQHandler +TIM5_IRQHandler +SPI3_IRQHandler +UART4_IRQHandler +UART5_IRQHandler +TIM6_IRQHandler +TIM7_IRQHandler +DMA2_Channel1_IRQHandler +DMA2_Channel2_IRQHandler +DMA2_Channel3_IRQHandler +DMA2_Channel4_5_IRQHandler + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s new file mode 100755 index 0000000000..039ec06ca0 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_cl.s @@ -0,0 +1,468 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_cl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Connectivity line Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR + * address. + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss + +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler + +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word CAN1_TX_IRQHandler + .word CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word OTG_FS_WKUP_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_IRQHandler + .word DMA2_Channel5_IRQHandler + .word ETH_IRQHandler + .word ETH_WKUP_IRQHandler + .word CAN2_TX_IRQHandler + .word CAN2_RX0_IRQHandler + .word CAN2_RX1_IRQHandler + .word CAN2_SCE_IRQHandler + .word OTG_FS_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x Connectivity line Devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_IRQHandler + .thumb_set DMA2_Channel4_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler ,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s new file mode 100755 index 0000000000..e4ba08c419 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd.s @@ -0,0 +1,465 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_IRQHandler + .word TIM8_UP_IRQHandler + .word TIM8_TRG_COM_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_IRQHandler + .thumb_set TIM8_BRK_IRQHandler,Default_Handler + + .weak TIM8_UP_IRQHandler + .thumb_set TIM8_UP_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_IRQHandler + .thumb_set TIM8_TRG_COM_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s new file mode 100755 index 0000000000..daad5cc34b --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_hd_vl.s @@ -0,0 +1,442 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_hd_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x High Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM32100E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word TIM12_IRQHandler + .word TIM13_IRQHandler + .word TIM14_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word DMA2_Channel5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x High Density Value line devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM12_IRQHandler + .thumb_set TIM12_IRQHandler,Default_Handler + + .weak TIM13_IRQHandler + .thumb_set TIM13_IRQHandler,Default_Handler + + .weak TIM14_IRQHandler + .thumb_set TIM14_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + + .weak DMA2_Channel5_IRQHandler + .thumb_set DMA2_Channel5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s new file mode 100755 index 0000000000..aaa09ecd4b --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld.s @@ -0,0 +1,343 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Low Density devices.*/ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s new file mode 100755 index 0000000000..d4401be2f5 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_ld_vl.s @@ -0,0 +1,383 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_ld_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Low Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word 0 + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word 0 + .word 0 + .word SPI1_IRQHandler + .word 0 + .word USART1_IRQHandler + .word USART2_IRQHandler + .word 0 + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Low Density Value Line devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s new file mode 100755 index 0000000000..4b4a0502be --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md.s @@ -0,0 +1,358 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s new file mode 100755 index 0000000000..8bce9979bc --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_md_vl.s @@ -0,0 +1,399 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md_vl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Value Line Devices vector table for RIDE7 + * toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM15_IRQHandler + .word TIM1_UP_TIM16_IRQHandler + .word TIM1_TRG_COM_TIM17_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word CEC_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word TIM6_DAC_IRQHandler + .word TIM7_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x01CC. This is for boot in RAM mode for + STM32F10x Medium Value Line Density devices. */ + +/******************************************************************************* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_IRQHandler + .thumb_set ADC1_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM15_IRQHandler + .thumb_set TIM1_BRK_TIM15_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM16_IRQHandler + .thumb_set TIM1_UP_TIM16_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM17_IRQHandler + .thumb_set TIM1_TRG_COM_TIM17_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak CEC_IRQHandler + .thumb_set CEC_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s new file mode 100755 index 0000000000..3d727a0d55 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/gcc_ride7/startup_stm32f10x_xl.s @@ -0,0 +1,465 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_xl.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x XL-Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM3210E-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +.equ BootRAM, 0xF1E0F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call the application's entry point.*/ + bl main + bx lr +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_TIM9_IRQHandler + .word TIM1_UP_TIM10_IRQHandler + .word TIM1_TRG_COM_TIM11_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word TIM8_BRK_TIM12_IRQHandler + .word TIM8_UP_TIM13_IRQHandler + .word TIM8_TRG_COM_TIM14_IRQHandler + .word TIM8_CC_IRQHandler + .word ADC3_IRQHandler + .word FSMC_IRQHandler + .word SDIO_IRQHandler + .word TIM5_IRQHandler + .word SPI3_IRQHandler + .word UART4_IRQHandler + .word UART5_IRQHandler + .word TIM6_IRQHandler + .word TIM7_IRQHandler + .word DMA2_Channel1_IRQHandler + .word DMA2_Channel2_IRQHandler + .word DMA2_Channel3_IRQHandler + .word DMA2_Channel4_5_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x1E0. This is for boot in RAM mode for + STM32F10x XL Density devices. */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak ADC3_IRQHandler + .thumb_set ADC3_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_IRQHandler + .thumb_set TIM6_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Channel1_IRQHandler + .thumb_set DMA2_Channel1_IRQHandler,Default_Handler + + .weak DMA2_Channel2_IRQHandler + .thumb_set DMA2_Channel2_IRQHandler,Default_Handler + + .weak DMA2_Channel3_IRQHandler + .thumb_set DMA2_Channel3_IRQHandler,Default_Handler + + .weak DMA2_Channel4_5_IRQHandler + .thumb_set DMA2_Channel4_5_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s new file mode 100755 index 0000000000..55a79320bd --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_cl.s @@ -0,0 +1,507 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************* +;* File Name : startup_stm32f10x_cl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Connectivity line devices vector table for +;* EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 and ADC2 + DCD CAN1_TX_IRQHandler ; CAN1 TX + DCD CAN1_RX0_IRQHandler ; CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C1 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC alarm through EXTI line + DCD OTG_FS_WKUP_IRQHandler ; USB OTG FS Wakeup through EXTI line + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + DCD ETH_IRQHandler ; Ethernet + DCD ETH_WKUP_IRQHandler ; Ethernet Wakeup through EXTI line + DCD CAN2_TX_IRQHandler ; CAN2 TX + DCD CAN2_RX0_IRQHandler ; CAN2 RX0 + DCD CAN2_RX1_IRQHandler ; CAN2 RX1 + DCD CAN2_SCE_IRQHandler ; CAN2 SCE + DCD OTG_FS_IRQHandler ; USB OTG FS + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_TX_IRQHandler + B CAN1_TX_IRQHandler + + PUBWEAK CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX0_IRQHandler + B CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK OTG_FS_WKUP_IRQHandler + SECTION .text:CODE:REORDER(1) +OTG_FS_WKUP_IRQHandler + B OTG_FS_WKUP_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_IRQHandler + B DMA2_Channel4_IRQHandler + + PUBWEAK DMA2_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel5_IRQHandler + B DMA2_Channel5_IRQHandler + + PUBWEAK ETH_IRQHandler + SECTION .text:CODE:REORDER(1) +ETH_IRQHandler + B ETH_IRQHandler + + PUBWEAK ETH_WKUP_IRQHandler + SECTION .text:CODE:REORDER(1) +ETH_WKUP_IRQHandler + B ETH_WKUP_IRQHandler + + PUBWEAK CAN2_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_TX_IRQHandler + B CAN2_TX_IRQHandler + + PUBWEAK CAN2_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_RX0_IRQHandler + B CAN2_RX0_IRQHandler + + PUBWEAK CAN2_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_RX1_IRQHandler + B CAN2_RX1_IRQHandler + + PUBWEAK CAN2_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN2_SCE_IRQHandler + B CAN2_SCE_IRQHandler + + PUBWEAK OTG_FS_IRQHandler + SECTION .text:CODE:REORDER(1) +OTG_FS_IRQHandler + B OTG_FS_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s new file mode 100755 index 0000000000..37ee7a203f --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd.s @@ -0,0 +1,496 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR address, +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA + +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_IRQHandler ; TIM8 Break + DCD TIM8_UP_IRQHandler ; TIM8 Update + DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger and Commutation + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + PUBWEAK TIM8_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_BRK_IRQHandler + B TIM8_BRK_IRQHandler + + PUBWEAK TIM8_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_UP_IRQHandler + B TIM8_UP_IRQHandler + + PUBWEAK TIM8_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_TRG_COM_IRQHandler + B TIM8_TRG_COM_IRQHandler + + PUBWEAK TIM8_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_CC_IRQHandler + B TIM8_CC_IRQHandler + + PUBWEAK ADC3_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC3_IRQHandler + B ADC3_IRQHandler + + PUBWEAK FSMC_IRQHandler + SECTION .text:CODE:REORDER(1) +FSMC_IRQHandler + B FSMC_IRQHandler + + PUBWEAK SDIO_IRQHandler + SECTION .text:CODE:REORDER(1) +SDIO_IRQHandler + B SDIO_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + + END + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s new file mode 100755 index 0000000000..33f592f1a5 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_hd_vl.s @@ -0,0 +1,461 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_hd_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x High Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM32100E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD TIM12_IRQHandler ; TIM12 + DCD TIM13_IRQHandler ; TIM13 + DCD TIM14_IRQHandler ; TIM14 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel5 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM12_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM12_IRQHandler + B TIM12_IRQHandler + + PUBWEAK TIM13_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM13_IRQHandler + B TIM13_IRQHandler + + PUBWEAK TIM14_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM14_IRQHandler + B TIM14_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + PUBWEAK DMA2_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel5_IRQHandler + B DMA2_Channel5_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s new file mode 100755 index 0000000000..e2b2b4df06 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld.s @@ -0,0 +1,366 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s new file mode 100755 index 0000000000..a4a49331c5 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_ld_vl.s @@ -0,0 +1,369 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_ld_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Low Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD 0 ; Reserved + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SPI1_IRQHandler ; SPI1 + DCD 0 ; Reserved + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD 0 ; Reserved + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s new file mode 100755 index 0000000000..5863eb90f4 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md.s @@ -0,0 +1,391 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for +;* EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_IRQHandler + B TIM1_BRK_IRQHandler + + PUBWEAK TIM1_UP_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_IRQHandler + B TIM1_UP_IRQHandler + + PUBWEAK TIM1_TRG_COM_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_IRQHandler + B TIM1_TRG_COM_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s new file mode 100755 index 0000000000..add509da6c --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_md_vl.s @@ -0,0 +1,394 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md_vl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Value Line Devices vector table +;* for EWARM toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_IRQHandler ; ADC1 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger and Commutation and TIM17 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD CEC_IRQHandler ; HDMI-CEC + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC underrun + DCD TIM7_IRQHandler ; TIM7 + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_IRQHandler + B ADC1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK CEC_IRQHandler + SECTION .text:CODE:REORDER(1) +CEC_IRQHandler + B CEC_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + END +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s new file mode 100755 index 0000000000..a7f49c56dd --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/startup/iar/startup_stm32f10x_xl.s @@ -0,0 +1,496 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_xl.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x XL-Density Devices vector table for EWARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Configure the clock system and the external SRAM +;* mounted on STM3210E-EVAL board to be used as data +;* memory (optional, to be enabled by user) +;* - Set the initial PC == __iar_program_start, +;* - Set the vector table entries with the exceptions ISR address, +;* After Reset the Cortex-M3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +;* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +;* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +;* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +;* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +;* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* +; +; +; The modules in this file are included in the libraries, and may be replaced +; by any user-defined modules that define the PUBLIC symbol _program_start or +; a user defined start symbol. +; To override the cstartup defined in the library, simply add your modified +; version to the workbench project. +; +; The vector table is normally located at address 0. +; When debugging in RAM, it can be located in RAM, aligned to at least 2^6. +; The name "__vector_table" has special meaning for C-SPY: +; it is where the SP start value is found, and the NVIC vector +; table register (VTOR) is initialized to this address if != 0. +; +; Cortex-M version +; + + MODULE ?cstartup + + ;; Forward declaration of sections. + SECTION CSTACK:DATA:NOROOT(3) + + SECTION .intvec:CODE:NOROOT(2) + + EXTERN __iar_program_start + EXTERN SystemInit + PUBLIC __vector_table + + DATA + +__vector_table + DCD sfe(CSTACK) + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1 & ADC2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_TIM9_IRQHandler ; TIM1 Break and TIM9 + DCD TIM1_UP_TIM10_IRQHandler ; TIM1 Update and TIM10 + DCD TIM1_TRG_COM_TIM11_IRQHandler ; TIM1 Trigger and Commutation and TIM11 + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend + DCD TIM8_BRK_TIM12_IRQHandler ; TIM8 Break and TIM12 + DCD TIM8_UP_TIM13_IRQHandler ; TIM8 Update and TIM13 + DCD TIM8_TRG_COM_TIM14_IRQHandler ; TIM8 Trigger and Commutation and TIM14 + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare + DCD ADC3_IRQHandler ; ADC3 + DCD FSMC_IRQHandler ; FSMC + DCD SDIO_IRQHandler ; SDIO + DCD TIM5_IRQHandler ; TIM5 + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD UART5_IRQHandler ; UART5 + DCD TIM6_IRQHandler ; TIM6 + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel3 + DCD DMA2_Channel4_5_IRQHandler ; DMA2 Channel4 & Channel5 +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + + PUBWEAK Reset_Handler + SECTION .text:CODE:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_IRQHandler + SECTION .text:CODE:REORDER(1) +PVD_IRQHandler + B PVD_IRQHandler + + PUBWEAK TAMPER_IRQHandler + SECTION .text:CODE:REORDER(1) +TAMPER_IRQHandler + B TAMPER_IRQHandler + + PUBWEAK RTC_IRQHandler + SECTION .text:CODE:REORDER(1) +RTC_IRQHandler + B RTC_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK DMA1_Channel7_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA1_Channel7_IRQHandler + B DMA1_Channel7_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_CAN1_TX_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_HP_CAN1_TX_IRQHandler + B USB_HP_CAN1_TX_IRQHandler + + PUBWEAK USB_LP_CAN1_RX0_IRQHandler + SECTION .text:CODE:REORDER(1) +USB_LP_CAN1_RX0_IRQHandler + B USB_LP_CAN1_RX0_IRQHandler + + PUBWEAK CAN1_RX1_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_RX1_IRQHandler + B CAN1_RX1_IRQHandler + + PUBWEAK CAN1_SCE_IRQHandler + SECTION .text:CODE:REORDER(1) +CAN1_SCE_IRQHandler + B CAN1_SCE_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM9_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_BRK_TIM9_IRQHandler + B TIM1_BRK_TIM9_IRQHandler + + PUBWEAK TIM1_UP_TIM10_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_UP_TIM10_IRQHandler + B TIM1_UP_TIM10_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM11_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_TRG_COM_TIM11_IRQHandler + B TIM1_TRG_COM_TIM11_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTCAlarm_IRQHandler + SECTION .text:CODE:REORDER(1) +RTCAlarm_IRQHandler + B RTCAlarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + PUBWEAK TIM8_BRK_TIM12_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_BRK_TIM12_IRQHandler + B TIM8_BRK_TIM12_IRQHandler + + PUBWEAK TIM8_UP_TIM13_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_UP_TIM13_IRQHandler + B TIM8_UP_TIM13_IRQHandler + + PUBWEAK TIM8_TRG_COM_TIM14_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_TRG_COM_TIM14_IRQHandler + B TIM8_TRG_COM_TIM14_IRQHandler + + PUBWEAK TIM8_CC_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM8_CC_IRQHandler + B TIM8_CC_IRQHandler + + PUBWEAK ADC3_IRQHandler + SECTION .text:CODE:REORDER(1) +ADC3_IRQHandler + B ADC3_IRQHandler + + PUBWEAK FSMC_IRQHandler + SECTION .text:CODE:REORDER(1) +FSMC_IRQHandler + B FSMC_IRQHandler + + PUBWEAK SDIO_IRQHandler + SECTION .text:CODE:REORDER(1) +SDIO_IRQHandler + B SDIO_IRQHandler + + PUBWEAK TIM5_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM5_IRQHandler + B TIM5_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK UART5_IRQHandler + SECTION .text:CODE:REORDER(1) +UART5_IRQHandler + B UART5_IRQHandler + + PUBWEAK TIM6_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM6_IRQHandler + B TIM6_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_5_IRQHandler + SECTION .text:CODE:REORDER(1) +DMA2_Channel4_5_IRQHandler + B DMA2_Channel4_5_IRQHandler + + + END + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h new file mode 100755 index 0000000000..af0c7c9af1 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x.h @@ -0,0 +1,8336 @@ +/** + ****************************************************************************** + * @file stm32f10x.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer Header File. + * This file contains all the peripheral register's definitions, bits + * definitions and memory mapping for STM32F10x Connectivity line, + * High density, High density value line, Medium density, + * Medium density Value line, Low density, Low density Value line + * and XL-density devices. + * + * The file is the unique include file that the application programmer + * is using in the C source code, usually in main.c. This file contains: + * - Configuration section that allows to select: + * - The device used in the target application + * - To use or not the peripheral’s drivers in application code(i.e. + * code will be based on direct access to peripheral’s registers + * rather than drivers API), this option is controlled by + * "#define USE_STDPERIPH_DRIVER" + * - To change few application-specific parameters such as the HSE + * crystal frequency + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral’s registers hardware + * + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x + * @{ + */ + +#ifndef __STM32F10x_H +#define __STM32F10x_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup Library_configuration_section + * @{ + */ + +/* Uncomment the line below according to the target STM32 device used in your + application + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + /* #define STM32F10X_LD */ /*!< STM32F10X_LD: STM32 Low density devices */ + /* #define STM32F10X_LD_VL */ /*!< STM32F10X_LD_VL: STM32 Low density Value Line devices */ + /* #define STM32F10X_MD */ /*!< STM32F10X_MD: STM32 Medium density devices */ + /* #define STM32F10X_MD_VL */ /*!< STM32F10X_MD_VL: STM32 Medium density Value Line devices */ + /* #define STM32F10X_HD */ /*!< STM32F10X_HD: STM32 High density devices */ + /* #define STM32F10X_HD_VL */ /*!< STM32F10X_HD_VL: STM32 High density value line devices */ + /* #define STM32F10X_XL */ /*!< STM32F10X_XL: STM32 XL-density devices */ + /* #define STM32F10X_CL */ /*!< STM32F10X_CL: STM32 Connectivity line devices */ +#endif +/* Tip: To avoid modifying this file each time you need to switch between these + devices, you can define the device in your toolchain compiler preprocessor. + + - Low-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 16 and 32 Kbytes. + - Low-density value line devices are STM32F100xx microcontrollers where the Flash + memory density ranges between 16 and 32 Kbytes. + - Medium-density devices are STM32F101xx, STM32F102xx and STM32F103xx microcontrollers + where the Flash memory density ranges between 64 and 128 Kbytes. + - Medium-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 64 and 128 Kbytes. + - High-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 256 and 512 Kbytes. + - High-density value line devices are STM32F100xx microcontrollers where the + Flash memory density ranges between 256 and 512 Kbytes. + - XL-density devices are STM32F101xx and STM32F103xx microcontrollers where + the Flash memory density ranges between 512 and 1024 Kbytes. + - Connectivity line devices are STM32F105xx and STM32F107xx microcontrollers. + */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_XL) && !defined (STM32F10X_CL) + #error "Please select first the target STM32F10x device used in your application (in stm32f10x.h file)" +#endif + +#if !defined USE_STDPERIPH_DRIVER +/** + * @brief Comment the line below if you will not use the peripherals drivers. + In this case, these drivers will not be included and the application code will + be based on direct access to peripherals registers + */ + /*#define USE_STDPERIPH_DRIVER*/ +#endif + +/** + * @brief In the following line adjust the value of External High Speed oscillator (HSE) + used in your application + + Tip: To avoid modifying this file each time you need to use different HSE, you + can define the HSE value in your toolchain compiler preprocessor. + */ +#if !defined HSE_VALUE + #ifdef STM32F10X_CL + #define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */ + #else + #define HSE_VALUE ((uint32_t)8000000) /*!< Value of the External oscillator in Hz */ + #endif /* STM32F10X_CL */ +#endif /* HSE_VALUE */ + + +/** + * @brief In the following line adjust the External High Speed oscillator (HSE) Startup + Timeout value + */ +#define HSE_STARTUP_TIMEOUT ((uint16_t)0x0500) /*!< Time out for HSE start up */ + +#define HSI_VALUE ((uint32_t)8000000) /*!< Value of the Internal oscillator in Hz*/ + +/** + * @brief STM32F10x Standard Peripheral Library version number + */ +#define __STM32F10X_STDPERIPH_VERSION_MAIN (0x03) /*!< [31:24] main version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB1 (0x05) /*!< [23:16] sub1 version */ +#define __STM32F10X_STDPERIPH_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ +#define __STM32F10X_STDPERIPH_VERSION_RC (0x00) /*!< [7:0] release candidate */ +#define __STM32F10X_STDPERIPH_VERSION ( (__STM32F10X_STDPERIPH_VERSION_MAIN << 24)\ + |(__STM32F10X_STDPERIPH_VERSION_SUB1 << 16)\ + |(__STM32F10X_STDPERIPH_VERSION_SUB2 << 8)\ + |(__STM32F10X_STDPERIPH_VERSION_RC)) + +/** + * @} + */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M3 Processor and Core Peripherals + */ +#ifdef STM32F10X_XL + #define __MPU_PRESENT 1 /*!< STM32 XL-density devices provide an MPU */ +#else + #define __MPU_PRESENT 0 /*!< Other STM32 devices does not provide an MPU */ +#endif /* STM32F10X_XL */ +#define __NVIC_PRIO_BITS 4 /*!< STM32 uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */ + +/** + * @brief STM32F10x Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum IRQn +{ +/****** Cortex-M3 Processor Exceptions Numbers ***************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M3 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M3 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M3 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M3 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M3 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M3 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M3 System Tick Interrupt */ + +/****** STM32 specific Interrupt Numbers *********************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ + TAMPER_IRQn = 2, /*!< Tamper Interrupt */ + RTC_IRQn = 3, /*!< RTC global Interrupt */ + FLASH_IRQn = 4, /*!< FLASH global Interrupt */ + RCC_IRQn = 5, /*!< RCC global Interrupt */ + EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ + EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ + EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ + EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ + EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ + DMA1_Channel1_IRQn = 11, /*!< DMA1 Channel 1 global Interrupt */ + DMA1_Channel2_IRQn = 12, /*!< DMA1 Channel 2 global Interrupt */ + DMA1_Channel3_IRQn = 13, /*!< DMA1 Channel 3 global Interrupt */ + DMA1_Channel4_IRQn = 14, /*!< DMA1 Channel 4 global Interrupt */ + DMA1_Channel5_IRQn = 15, /*!< DMA1 Channel 5 global Interrupt */ + DMA1_Channel6_IRQn = 16, /*!< DMA1 Channel 6 global Interrupt */ + DMA1_Channel7_IRQn = 17, /*!< DMA1 Channel 7 global Interrupt */ + +#ifdef STM32F10X_LD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_LD */ + +#ifdef STM32F10X_LD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_LD_VL */ + +#ifdef STM32F10X_MD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42 /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ +#endif /* STM32F10X_MD */ + +#ifdef STM32F10X_MD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55 /*!< TIM7 Interrupt */ +#endif /* STM32F10X_MD_VL */ + +#ifdef STM32F10X_HD + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_IRQn = 43, /*!< TIM8 Break Interrupt */ + TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ + TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_HD */ + +#ifdef STM32F10X_HD_VL + ADC1_IRQn = 18, /*!< ADC1 global Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break and TIM15 Interrupts */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update and TIM16 Interrupts */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + CEC_IRQn = 42, /*!< HDMI-CEC Interrupt */ + TIM12_IRQn = 43, /*!< TIM12 global Interrupt */ + TIM13_IRQn = 44, /*!< TIM13 global Interrupt */ + TIM14_IRQn = 45, /*!< TIM14 global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 and DAC underrun Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59, /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ + DMA2_Channel5_IRQn = 60 /*!< DMA2 Channel 5 global Interrupt (DMA2 Channel 5 is + mapped at position 60 only if the MISC_REMAP bit in + the AFIO_MAPR2 register is set) */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_XL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + USB_LP_CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break Interrupt and TIM9 global Interrupt */ + TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global Interrupt */ + TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Device WakeUp from suspend through EXTI Line Interrupt */ + TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global Interrupt */ + TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global Interrupt */ + TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + ADC3_IRQn = 47, /*!< ADC3 global Interrupt */ + FSMC_IRQn = 48, /*!< FSMC global Interrupt */ + SDIO_IRQn = 49, /*!< SDIO global Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_5_IRQn = 59 /*!< DMA2 Channel 4 and Channel 5 global Interrupt */ +#endif /* STM32F10X_XL */ + +#ifdef STM32F10X_CL + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + CAN1_TX_IRQn = 19, /*!< USB Device High Priority or CAN1 TX Interrupts */ + CAN1_RX0_IRQn = 20, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */ + CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ + CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ + TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ + TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ + TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ + TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ + TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ + TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ + I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ + I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ + I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ + I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ + SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ + SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ + USART1_IRQn = 37, /*!< USART1 global Interrupt */ + USART2_IRQn = 38, /*!< USART2 global Interrupt */ + USART3_IRQn = 39, /*!< USART3 global Interrupt */ + EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ + RTCAlarm_IRQn = 41, /*!< RTC Alarm through EXTI Line Interrupt */ + OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS WakeUp from suspend through EXTI Line Interrupt */ + TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + UART5_IRQn = 53, /*!< UART5 global Interrupt */ + TIM6_IRQn = 54, /*!< TIM6 global Interrupt */ + TIM7_IRQn = 55, /*!< TIM7 global Interrupt */ + DMA2_Channel1_IRQn = 56, /*!< DMA2 Channel 1 global Interrupt */ + DMA2_Channel2_IRQn = 57, /*!< DMA2 Channel 2 global Interrupt */ + DMA2_Channel3_IRQn = 58, /*!< DMA2 Channel 3 global Interrupt */ + DMA2_Channel4_IRQn = 59, /*!< DMA2 Channel 4 global Interrupt */ + DMA2_Channel5_IRQn = 60, /*!< DMA2 Channel 5 global Interrupt */ + ETH_IRQn = 61, /*!< Ethernet global Interrupt */ + ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ + CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ + CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ + CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ + CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ + OTG_FS_IRQn = 67 /*!< USB OTG FS global Interrupt */ +#endif /* STM32F10X_CL */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm3.h" +#include "system_stm32f10x.h" +#include + +/** @addtogroup Exported_types + * @{ + */ + +/*!< STM32F10x Standard Peripheral Library old types (maintained for legacy purpose) */ +typedef int32_t s32; +typedef int16_t s16; +typedef int8_t s8; + +typedef const int32_t sc32; /*!< Read Only */ +typedef const int16_t sc16; /*!< Read Only */ +typedef const int8_t sc8; /*!< Read Only */ + +typedef __IO int32_t vs32; +typedef __IO int16_t vs16; +typedef __IO int8_t vs8; + +typedef __I int32_t vsc32; /*!< Read Only */ +typedef __I int16_t vsc16; /*!< Read Only */ +typedef __I int8_t vsc8; /*!< Read Only */ + +typedef uint32_t u32; +typedef uint16_t u16; +typedef uint8_t u8; + +typedef const uint32_t uc32; /*!< Read Only */ +typedef const uint16_t uc16; /*!< Read Only */ +typedef const uint8_t uc8; /*!< Read Only */ + +typedef __IO uint32_t vu32; +typedef __IO uint16_t vu16; +typedef __IO uint8_t vu8; + +typedef __I uint32_t vuc32; /*!< Read Only */ +typedef __I uint16_t vuc16; /*!< Read Only */ +typedef __I uint8_t vuc8; /*!< Read Only */ + +typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus; + +typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; +#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) + +typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus; + +/*!< STM32F10x Standard Peripheral Library old definitions (maintained for legacy purpose) */ +#define HSEStartUp_TimeOut HSE_STARTUP_TIMEOUT +#define HSE_Value HSE_VALUE +#define HSI_Value HSI_VALUE +/** + * @} + */ + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t SR; + __IO uint32_t CR1; + __IO uint32_t CR2; + __IO uint32_t SMPR1; + __IO uint32_t SMPR2; + __IO uint32_t JOFR1; + __IO uint32_t JOFR2; + __IO uint32_t JOFR3; + __IO uint32_t JOFR4; + __IO uint32_t HTR; + __IO uint32_t LTR; + __IO uint32_t SQR1; + __IO uint32_t SQR2; + __IO uint32_t SQR3; + __IO uint32_t JSQR; + __IO uint32_t JDR1; + __IO uint32_t JDR2; + __IO uint32_t JDR3; + __IO uint32_t JDR4; + __IO uint32_t DR; +} ADC_TypeDef; + +/** + * @brief Backup Registers + */ + +typedef struct +{ + uint32_t RESERVED0; + __IO uint16_t DR1; + uint16_t RESERVED1; + __IO uint16_t DR2; + uint16_t RESERVED2; + __IO uint16_t DR3; + uint16_t RESERVED3; + __IO uint16_t DR4; + uint16_t RESERVED4; + __IO uint16_t DR5; + uint16_t RESERVED5; + __IO uint16_t DR6; + uint16_t RESERVED6; + __IO uint16_t DR7; + uint16_t RESERVED7; + __IO uint16_t DR8; + uint16_t RESERVED8; + __IO uint16_t DR9; + uint16_t RESERVED9; + __IO uint16_t DR10; + uint16_t RESERVED10; + __IO uint16_t RTCCR; + uint16_t RESERVED11; + __IO uint16_t CR; + uint16_t RESERVED12; + __IO uint16_t CSR; + uint16_t RESERVED13[5]; + __IO uint16_t DR11; + uint16_t RESERVED14; + __IO uint16_t DR12; + uint16_t RESERVED15; + __IO uint16_t DR13; + uint16_t RESERVED16; + __IO uint16_t DR14; + uint16_t RESERVED17; + __IO uint16_t DR15; + uint16_t RESERVED18; + __IO uint16_t DR16; + uint16_t RESERVED19; + __IO uint16_t DR17; + uint16_t RESERVED20; + __IO uint16_t DR18; + uint16_t RESERVED21; + __IO uint16_t DR19; + uint16_t RESERVED22; + __IO uint16_t DR20; + uint16_t RESERVED23; + __IO uint16_t DR21; + uint16_t RESERVED24; + __IO uint16_t DR22; + uint16_t RESERVED25; + __IO uint16_t DR23; + uint16_t RESERVED26; + __IO uint16_t DR24; + uint16_t RESERVED27; + __IO uint16_t DR25; + uint16_t RESERVED28; + __IO uint16_t DR26; + uint16_t RESERVED29; + __IO uint16_t DR27; + uint16_t RESERVED30; + __IO uint16_t DR28; + uint16_t RESERVED31; + __IO uint16_t DR29; + uint16_t RESERVED32; + __IO uint16_t DR30; + uint16_t RESERVED33; + __IO uint16_t DR31; + uint16_t RESERVED34; + __IO uint16_t DR32; + uint16_t RESERVED35; + __IO uint16_t DR33; + uint16_t RESERVED36; + __IO uint16_t DR34; + uint16_t RESERVED37; + __IO uint16_t DR35; + uint16_t RESERVED38; + __IO uint16_t DR36; + uint16_t RESERVED39; + __IO uint16_t DR37; + uint16_t RESERVED40; + __IO uint16_t DR38; + uint16_t RESERVED41; + __IO uint16_t DR39; + uint16_t RESERVED42; + __IO uint16_t DR40; + uint16_t RESERVED43; + __IO uint16_t DR41; + uint16_t RESERVED44; + __IO uint16_t DR42; + uint16_t RESERVED45; +} BKP_TypeDef; + +/** + * @brief Controller Area Network TxMailBox + */ + +typedef struct +{ + __IO uint32_t TIR; + __IO uint32_t TDTR; + __IO uint32_t TDLR; + __IO uint32_t TDHR; +} CAN_TxMailBox_TypeDef; + +/** + * @brief Controller Area Network FIFOMailBox + */ + +typedef struct +{ + __IO uint32_t RIR; + __IO uint32_t RDTR; + __IO uint32_t RDLR; + __IO uint32_t RDHR; +} CAN_FIFOMailBox_TypeDef; + +/** + * @brief Controller Area Network FilterRegister + */ + +typedef struct +{ + __IO uint32_t FR1; + __IO uint32_t FR2; +} CAN_FilterRegister_TypeDef; + +/** + * @brief Controller Area Network + */ + +typedef struct +{ + __IO uint32_t MCR; + __IO uint32_t MSR; + __IO uint32_t TSR; + __IO uint32_t RF0R; + __IO uint32_t RF1R; + __IO uint32_t IER; + __IO uint32_t ESR; + __IO uint32_t BTR; + uint32_t RESERVED0[88]; + CAN_TxMailBox_TypeDef sTxMailBox[3]; + CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; + uint32_t RESERVED1[12]; + __IO uint32_t FMR; + __IO uint32_t FM1R; + uint32_t RESERVED2; + __IO uint32_t FS1R; + uint32_t RESERVED3; + __IO uint32_t FFA1R; + uint32_t RESERVED4; + __IO uint32_t FA1R; + uint32_t RESERVED5[8]; +#ifndef STM32F10X_CL + CAN_FilterRegister_TypeDef sFilterRegister[14]; +#else + CAN_FilterRegister_TypeDef sFilterRegister[28]; +#endif /* STM32F10X_CL */ +} CAN_TypeDef; + +/** + * @brief Consumer Electronics Control (CEC) + */ +typedef struct +{ + __IO uint32_t CFGR; + __IO uint32_t OAR; + __IO uint32_t PRES; + __IO uint32_t ESR; + __IO uint32_t CSR; + __IO uint32_t TXD; + __IO uint32_t RXD; +} CEC_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; + __IO uint8_t IDR; + uint8_t RESERVED0; + uint16_t RESERVED1; + __IO uint32_t CR; +} CRC_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t SWTRIGR; + __IO uint32_t DHR12R1; + __IO uint32_t DHR12L1; + __IO uint32_t DHR8R1; + __IO uint32_t DHR12R2; + __IO uint32_t DHR12L2; + __IO uint32_t DHR8R2; + __IO uint32_t DHR12RD; + __IO uint32_t DHR12LD; + __IO uint32_t DHR8RD; + __IO uint32_t DOR1; + __IO uint32_t DOR2; +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + __IO uint32_t SR; +#endif +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; + __IO uint32_t CR; +}DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; + __IO uint32_t CNDTR; + __IO uint32_t CPAR; + __IO uint32_t CMAR; +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; + __IO uint32_t IFCR; +} DMA_TypeDef; + +/** + * @brief Ethernet MAC + */ + +typedef struct +{ + __IO uint32_t MACCR; + __IO uint32_t MACFFR; + __IO uint32_t MACHTHR; + __IO uint32_t MACHTLR; + __IO uint32_t MACMIIAR; + __IO uint32_t MACMIIDR; + __IO uint32_t MACFCR; + __IO uint32_t MACVLANTR; /* 8 */ + uint32_t RESERVED0[2]; + __IO uint32_t MACRWUFFR; /* 11 */ + __IO uint32_t MACPMTCSR; + uint32_t RESERVED1[2]; + __IO uint32_t MACSR; /* 15 */ + __IO uint32_t MACIMR; + __IO uint32_t MACA0HR; + __IO uint32_t MACA0LR; + __IO uint32_t MACA1HR; + __IO uint32_t MACA1LR; + __IO uint32_t MACA2HR; + __IO uint32_t MACA2LR; + __IO uint32_t MACA3HR; + __IO uint32_t MACA3LR; /* 24 */ + uint32_t RESERVED2[40]; + __IO uint32_t MMCCR; /* 65 */ + __IO uint32_t MMCRIR; + __IO uint32_t MMCTIR; + __IO uint32_t MMCRIMR; + __IO uint32_t MMCTIMR; /* 69 */ + uint32_t RESERVED3[14]; + __IO uint32_t MMCTGFSCCR; /* 84 */ + __IO uint32_t MMCTGFMSCCR; + uint32_t RESERVED4[5]; + __IO uint32_t MMCTGFCR; + uint32_t RESERVED5[10]; + __IO uint32_t MMCRFCECR; + __IO uint32_t MMCRFAECR; + uint32_t RESERVED6[10]; + __IO uint32_t MMCRGUFCR; + uint32_t RESERVED7[334]; + __IO uint32_t PTPTSCR; + __IO uint32_t PTPSSIR; + __IO uint32_t PTPTSHR; + __IO uint32_t PTPTSLR; + __IO uint32_t PTPTSHUR; + __IO uint32_t PTPTSLUR; + __IO uint32_t PTPTSAR; + __IO uint32_t PTPTTHR; + __IO uint32_t PTPTTLR; + uint32_t RESERVED8[567]; + __IO uint32_t DMABMR; + __IO uint32_t DMATPDR; + __IO uint32_t DMARPDR; + __IO uint32_t DMARDLAR; + __IO uint32_t DMATDLAR; + __IO uint32_t DMASR; + __IO uint32_t DMAOMR; + __IO uint32_t DMAIER; + __IO uint32_t DMAMFBOCR; + uint32_t RESERVED9[9]; + __IO uint32_t DMACHTDR; + __IO uint32_t DMACHRDR; + __IO uint32_t DMACHTBAR; + __IO uint32_t DMACHRBAR; +} ETH_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR; + __IO uint32_t EMR; + __IO uint32_t RTSR; + __IO uint32_t FTSR; + __IO uint32_t SWIER; + __IO uint32_t PR; +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; + __IO uint32_t KEYR; + __IO uint32_t OPTKEYR; + __IO uint32_t SR; + __IO uint32_t CR; + __IO uint32_t AR; + __IO uint32_t RESERVED; + __IO uint32_t OBR; + __IO uint32_t WRPR; +#ifdef STM32F10X_XL + uint32_t RESERVED1[8]; + __IO uint32_t KEYR2; + uint32_t RESERVED2; + __IO uint32_t SR2; + __IO uint32_t CR2; + __IO uint32_t AR2; +#endif /* STM32F10X_XL */ +} FLASH_TypeDef; + +/** + * @brief Option Bytes Registers + */ + +typedef struct +{ + __IO uint16_t RDP; + __IO uint16_t USER; + __IO uint16_t Data0; + __IO uint16_t Data1; + __IO uint16_t WRP0; + __IO uint16_t WRP1; + __IO uint16_t WRP2; + __IO uint16_t WRP3; +} OB_TypeDef; + +/** + * @brief Flexible Static Memory Controller + */ + +typedef struct +{ + __IO uint32_t BTCR[8]; +} FSMC_Bank1_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank1E + */ + +typedef struct +{ + __IO uint32_t BWTR[7]; +} FSMC_Bank1E_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank2 + */ + +typedef struct +{ + __IO uint32_t PCR2; + __IO uint32_t SR2; + __IO uint32_t PMEM2; + __IO uint32_t PATT2; + uint32_t RESERVED0; + __IO uint32_t ECCR2; +} FSMC_Bank2_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank3 + */ + +typedef struct +{ + __IO uint32_t PCR3; + __IO uint32_t SR3; + __IO uint32_t PMEM3; + __IO uint32_t PATT3; + uint32_t RESERVED0; + __IO uint32_t ECCR3; +} FSMC_Bank3_TypeDef; + +/** + * @brief Flexible Static Memory Controller Bank4 + */ + +typedef struct +{ + __IO uint32_t PCR4; + __IO uint32_t SR4; + __IO uint32_t PMEM4; + __IO uint32_t PATT4; + __IO uint32_t PIO4; +} FSMC_Bank4_TypeDef; + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t CRL; + __IO uint32_t CRH; + __IO uint32_t IDR; + __IO uint32_t ODR; + __IO uint32_t BSRR; + __IO uint32_t BRR; + __IO uint32_t LCKR; +} GPIO_TypeDef; + +/** + * @brief Alternate Function I/O + */ + +typedef struct +{ + __IO uint32_t EVCR; + __IO uint32_t MAPR; + __IO uint32_t EXTICR[4]; + uint32_t RESERVED0; + __IO uint32_t MAPR2; +} AFIO_TypeDef; +/** + * @brief Inter Integrated Circuit Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t OAR1; + uint16_t RESERVED2; + __IO uint16_t OAR2; + uint16_t RESERVED3; + __IO uint16_t DR; + uint16_t RESERVED4; + __IO uint16_t SR1; + uint16_t RESERVED5; + __IO uint16_t SR2; + uint16_t RESERVED6; + __IO uint16_t CCR; + uint16_t RESERVED7; + __IO uint16_t TRISE; + uint16_t RESERVED8; +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; + __IO uint32_t PR; + __IO uint32_t RLR; + __IO uint32_t SR; +} IWDG_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CSR; +} PWR_TypeDef; + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFGR; + __IO uint32_t CIR; + __IO uint32_t APB2RSTR; + __IO uint32_t APB1RSTR; + __IO uint32_t AHBENR; + __IO uint32_t APB2ENR; + __IO uint32_t APB1ENR; + __IO uint32_t BDCR; + __IO uint32_t CSR; + +#ifdef STM32F10X_CL + __IO uint32_t AHBRSTR; + __IO uint32_t CFGR2; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t RESERVED0; + __IO uint32_t CFGR2; +#endif /* STM32F10X_LD_VL || STM32F10X_MD_VL || STM32F10X_HD_VL */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ + +typedef struct +{ + __IO uint16_t CRH; + uint16_t RESERVED0; + __IO uint16_t CRL; + uint16_t RESERVED1; + __IO uint16_t PRLH; + uint16_t RESERVED2; + __IO uint16_t PRLL; + uint16_t RESERVED3; + __IO uint16_t DIVH; + uint16_t RESERVED4; + __IO uint16_t DIVL; + uint16_t RESERVED5; + __IO uint16_t CNTH; + uint16_t RESERVED6; + __IO uint16_t CNTL; + uint16_t RESERVED7; + __IO uint16_t ALRH; + uint16_t RESERVED8; + __IO uint16_t ALRL; + uint16_t RESERVED9; +} RTC_TypeDef; + +/** + * @brief SD host Interface + */ + +typedef struct +{ + __IO uint32_t POWER; + __IO uint32_t CLKCR; + __IO uint32_t ARG; + __IO uint32_t CMD; + __I uint32_t RESPCMD; + __I uint32_t RESP1; + __I uint32_t RESP2; + __I uint32_t RESP3; + __I uint32_t RESP4; + __IO uint32_t DTIMER; + __IO uint32_t DLEN; + __IO uint32_t DCTRL; + __I uint32_t DCOUNT; + __I uint32_t STA; + __IO uint32_t ICR; + __IO uint32_t MASK; + uint32_t RESERVED0[2]; + __I uint32_t FIFOCNT; + uint32_t RESERVED1[13]; + __IO uint32_t FIFO; +} SDIO_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SR; + uint16_t RESERVED2; + __IO uint16_t DR; + uint16_t RESERVED3; + __IO uint16_t CRCPR; + uint16_t RESERVED4; + __IO uint16_t RXCRCR; + uint16_t RESERVED5; + __IO uint16_t TXCRCR; + uint16_t RESERVED6; + __IO uint16_t I2SCFGR; + uint16_t RESERVED7; + __IO uint16_t I2SPR; + uint16_t RESERVED8; +} SPI_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint16_t CR1; + uint16_t RESERVED0; + __IO uint16_t CR2; + uint16_t RESERVED1; + __IO uint16_t SMCR; + uint16_t RESERVED2; + __IO uint16_t DIER; + uint16_t RESERVED3; + __IO uint16_t SR; + uint16_t RESERVED4; + __IO uint16_t EGR; + uint16_t RESERVED5; + __IO uint16_t CCMR1; + uint16_t RESERVED6; + __IO uint16_t CCMR2; + uint16_t RESERVED7; + __IO uint16_t CCER; + uint16_t RESERVED8; + __IO uint16_t CNT; + uint16_t RESERVED9; + __IO uint16_t PSC; + uint16_t RESERVED10; + __IO uint16_t ARR; + uint16_t RESERVED11; + __IO uint16_t RCR; + uint16_t RESERVED12; + __IO uint16_t CCR1; + uint16_t RESERVED13; + __IO uint16_t CCR2; + uint16_t RESERVED14; + __IO uint16_t CCR3; + uint16_t RESERVED15; + __IO uint16_t CCR4; + uint16_t RESERVED16; + __IO uint16_t BDTR; + uint16_t RESERVED17; + __IO uint16_t DCR; + uint16_t RESERVED18; + __IO uint16_t DMAR; + uint16_t RESERVED19; +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ + +typedef struct +{ + __IO uint16_t SR; + uint16_t RESERVED0; + __IO uint16_t DR; + uint16_t RESERVED1; + __IO uint16_t BRR; + uint16_t RESERVED2; + __IO uint16_t CR1; + uint16_t RESERVED3; + __IO uint16_t CR2; + uint16_t RESERVED4; + __IO uint16_t CR3; + uint16_t RESERVED5; + __IO uint16_t GTPR; + uint16_t RESERVED6; +} USART_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; + __IO uint32_t CFR; + __IO uint32_t SR; +} WWDG_TypeDef; + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + + +#define FLASH_BASE ((uint32_t)0x08000000) /*!< FLASH base address in the alias region */ +#define SRAM_BASE ((uint32_t)0x20000000) /*!< SRAM base address in the alias region */ +#define PERIPH_BASE ((uint32_t)0x40000000) /*!< Peripheral base address in the alias region */ + +#define SRAM_BB_BASE ((uint32_t)0x22000000) /*!< SRAM base address in the bit-band region */ +#define PERIPH_BB_BASE ((uint32_t)0x42000000) /*!< Peripheral base address in the bit-band region */ + +#define FSMC_R_BASE ((uint32_t)0xA0000000) /*!< FSMC registers base address */ + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x10000) +#define AHBPERIPH_BASE (PERIPH_BASE + 0x20000) + +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800) +#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400) +#define TIM12_BASE (APB1PERIPH_BASE + 0x1800) +#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00) +#define TIM14_BASE (APB1PERIPH_BASE + 0x2000) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00) +#define UART5_BASE (APB1PERIPH_BASE + 0x5000) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800) +#define CAN1_BASE (APB1PERIPH_BASE + 0x6400) +#define CAN2_BASE (APB1PERIPH_BASE + 0x6800) +#define BKP_BASE (APB1PERIPH_BASE + 0x6C00) +#define PWR_BASE (APB1PERIPH_BASE + 0x7000) +#define DAC_BASE (APB1PERIPH_BASE + 0x7400) +#define CEC_BASE (APB1PERIPH_BASE + 0x7800) + +#define AFIO_BASE (APB2PERIPH_BASE + 0x0000) +#define EXTI_BASE (APB2PERIPH_BASE + 0x0400) +#define GPIOA_BASE (APB2PERIPH_BASE + 0x0800) +#define GPIOB_BASE (APB2PERIPH_BASE + 0x0C00) +#define GPIOC_BASE (APB2PERIPH_BASE + 0x1000) +#define GPIOD_BASE (APB2PERIPH_BASE + 0x1400) +#define GPIOE_BASE (APB2PERIPH_BASE + 0x1800) +#define GPIOF_BASE (APB2PERIPH_BASE + 0x1C00) +#define GPIOG_BASE (APB2PERIPH_BASE + 0x2000) +#define ADC1_BASE (APB2PERIPH_BASE + 0x2400) +#define ADC2_BASE (APB2PERIPH_BASE + 0x2800) +#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000) +#define TIM8_BASE (APB2PERIPH_BASE + 0x3400) +#define USART1_BASE (APB2PERIPH_BASE + 0x3800) +#define ADC3_BASE (APB2PERIPH_BASE + 0x3C00) +#define TIM15_BASE (APB2PERIPH_BASE + 0x4000) +#define TIM16_BASE (APB2PERIPH_BASE + 0x4400) +#define TIM17_BASE (APB2PERIPH_BASE + 0x4800) +#define TIM9_BASE (APB2PERIPH_BASE + 0x4C00) +#define TIM10_BASE (APB2PERIPH_BASE + 0x5000) +#define TIM11_BASE (APB2PERIPH_BASE + 0x5400) + +#define SDIO_BASE (PERIPH_BASE + 0x18000) + +#define DMA1_BASE (AHBPERIPH_BASE + 0x0000) +#define DMA1_Channel1_BASE (AHBPERIPH_BASE + 0x0008) +#define DMA1_Channel2_BASE (AHBPERIPH_BASE + 0x001C) +#define DMA1_Channel3_BASE (AHBPERIPH_BASE + 0x0030) +#define DMA1_Channel4_BASE (AHBPERIPH_BASE + 0x0044) +#define DMA1_Channel5_BASE (AHBPERIPH_BASE + 0x0058) +#define DMA1_Channel6_BASE (AHBPERIPH_BASE + 0x006C) +#define DMA1_Channel7_BASE (AHBPERIPH_BASE + 0x0080) +#define DMA2_BASE (AHBPERIPH_BASE + 0x0400) +#define DMA2_Channel1_BASE (AHBPERIPH_BASE + 0x0408) +#define DMA2_Channel2_BASE (AHBPERIPH_BASE + 0x041C) +#define DMA2_Channel3_BASE (AHBPERIPH_BASE + 0x0430) +#define DMA2_Channel4_BASE (AHBPERIPH_BASE + 0x0444) +#define DMA2_Channel5_BASE (AHBPERIPH_BASE + 0x0458) +#define RCC_BASE (AHBPERIPH_BASE + 0x1000) +#define CRC_BASE (AHBPERIPH_BASE + 0x3000) + +#define FLASH_R_BASE (AHBPERIPH_BASE + 0x2000) /*!< Flash registers base address */ +#define OB_BASE ((uint32_t)0x1FFFF800) /*!< Flash Option Bytes base address */ + +#define ETH_BASE (AHBPERIPH_BASE + 0x8000) +#define ETH_MAC_BASE (ETH_BASE) +#define ETH_MMC_BASE (ETH_BASE + 0x0100) +#define ETH_PTP_BASE (ETH_BASE + 0x0700) +#define ETH_DMA_BASE (ETH_BASE + 0x1000) + +#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000) /*!< FSMC Bank1 registers base address */ +#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104) /*!< FSMC Bank1E registers base address */ +#define FSMC_Bank2_R_BASE (FSMC_R_BASE + 0x0060) /*!< FSMC Bank2 registers base address */ +#define FSMC_Bank3_R_BASE (FSMC_R_BASE + 0x0080) /*!< FSMC Bank3 registers base address */ +#define FSMC_Bank4_R_BASE (FSMC_R_BASE + 0x00A0) /*!< FSMC Bank4 registers base address */ + +#define DBGMCU_BASE ((uint32_t)0xE0042000) /*!< Debug MCU registers base address */ + +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ + +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM5 ((TIM_TypeDef *) TIM5_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define TIM12 ((TIM_TypeDef *) TIM12_BASE) +#define TIM13 ((TIM_TypeDef *) TIM13_BASE) +#define TIM14 ((TIM_TypeDef *) TIM14_BASE) +#define RTC ((RTC_TypeDef *) RTC_BASE) +#define WWDG ((WWDG_TypeDef *) WWDG_BASE) +#define IWDG ((IWDG_TypeDef *) IWDG_BASE) +#define SPI2 ((SPI_TypeDef *) SPI2_BASE) +#define SPI3 ((SPI_TypeDef *) SPI3_BASE) +#define USART2 ((USART_TypeDef *) USART2_BASE) +#define USART3 ((USART_TypeDef *) USART3_BASE) +#define UART4 ((USART_TypeDef *) UART4_BASE) +#define UART5 ((USART_TypeDef *) UART5_BASE) +#define I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define CAN1 ((CAN_TypeDef *) CAN1_BASE) +#define CAN2 ((CAN_TypeDef *) CAN2_BASE) +#define BKP ((BKP_TypeDef *) BKP_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define CEC ((CEC_TypeDef *) CEC_BASE) +#define AFIO ((AFIO_TypeDef *) AFIO_BASE) +#define EXTI ((EXTI_TypeDef *) EXTI_BASE) +#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) +#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) +#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) +#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) +#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) +#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) +#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) +#define ADC1 ((ADC_TypeDef *) ADC1_BASE) +#define ADC2 ((ADC_TypeDef *) ADC2_BASE) +#define TIM1 ((TIM_TypeDef *) TIM1_BASE) +#define SPI1 ((SPI_TypeDef *) SPI1_BASE) +#define TIM8 ((TIM_TypeDef *) TIM8_BASE) +#define USART1 ((USART_TypeDef *) USART1_BASE) +#define ADC3 ((ADC_TypeDef *) ADC3_BASE) +#define TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_BASE) +#define TIM9 ((TIM_TypeDef *) TIM9_BASE) +#define TIM10 ((TIM_TypeDef *) TIM10_BASE) +#define TIM11 ((TIM_TypeDef *) TIM11_BASE) +#define SDIO ((SDIO_TypeDef *) SDIO_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMA1_Channel1 ((DMA_Channel_TypeDef *) DMA1_Channel1_BASE) +#define DMA1_Channel2 ((DMA_Channel_TypeDef *) DMA1_Channel2_BASE) +#define DMA1_Channel3 ((DMA_Channel_TypeDef *) DMA1_Channel3_BASE) +#define DMA1_Channel4 ((DMA_Channel_TypeDef *) DMA1_Channel4_BASE) +#define DMA1_Channel5 ((DMA_Channel_TypeDef *) DMA1_Channel5_BASE) +#define DMA1_Channel6 ((DMA_Channel_TypeDef *) DMA1_Channel6_BASE) +#define DMA1_Channel7 ((DMA_Channel_TypeDef *) DMA1_Channel7_BASE) +#define DMA2_Channel1 ((DMA_Channel_TypeDef *) DMA2_Channel1_BASE) +#define DMA2_Channel2 ((DMA_Channel_TypeDef *) DMA2_Channel2_BASE) +#define DMA2_Channel3 ((DMA_Channel_TypeDef *) DMA2_Channel3_BASE) +#define DMA2_Channel4 ((DMA_Channel_TypeDef *) DMA2_Channel4_BASE) +#define DMA2_Channel5 ((DMA_Channel_TypeDef *) DMA2_Channel5_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define CRC ((CRC_TypeDef *) CRC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define OB ((OB_TypeDef *) OB_BASE) +#define ETH ((ETH_TypeDef *) ETH_BASE) +#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) +#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) +#define FSMC_Bank2 ((FSMC_Bank2_TypeDef *) FSMC_Bank2_R_BASE) +#define FSMC_Bank3 ((FSMC_Bank3_TypeDef *) FSMC_Bank3_R_BASE) +#define FSMC_Bank4 ((FSMC_Bank4_TypeDef *) FSMC_Bank4_R_BASE) +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* CRC calculation unit */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for CRC_DR register *********************/ +#define CRC_DR_DR ((uint32_t)0xFFFFFFFF) /*!< Data register bits */ + + +/******************* Bit definition for CRC_IDR register ********************/ +#define CRC_IDR_IDR ((uint8_t)0xFF) /*!< General-purpose 8-bit data register bits */ + + +/******************** Bit definition for CRC_CR register ********************/ +#define CRC_CR_RESET ((uint8_t)0x01) /*!< RESET bit */ + +/******************************************************************************/ +/* */ +/* Power Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for PWR_CR register ********************/ +#define PWR_CR_LPDS ((uint16_t)0x0001) /*!< Low-Power Deepsleep */ +#define PWR_CR_PDDS ((uint16_t)0x0002) /*!< Power Down Deepsleep */ +#define PWR_CR_CWUF ((uint16_t)0x0004) /*!< Clear Wakeup Flag */ +#define PWR_CR_CSBF ((uint16_t)0x0008) /*!< Clear Standby Flag */ +#define PWR_CR_PVDE ((uint16_t)0x0010) /*!< Power Voltage Detector Enable */ + +#define PWR_CR_PLS ((uint16_t)0x00E0) /*!< PLS[2:0] bits (PVD Level Selection) */ +#define PWR_CR_PLS_0 ((uint16_t)0x0020) /*!< Bit 0 */ +#define PWR_CR_PLS_1 ((uint16_t)0x0040) /*!< Bit 1 */ +#define PWR_CR_PLS_2 ((uint16_t)0x0080) /*!< Bit 2 */ + +/*!< PVD level configuration */ +#define PWR_CR_PLS_2V2 ((uint16_t)0x0000) /*!< PVD level 2.2V */ +#define PWR_CR_PLS_2V3 ((uint16_t)0x0020) /*!< PVD level 2.3V */ +#define PWR_CR_PLS_2V4 ((uint16_t)0x0040) /*!< PVD level 2.4V */ +#define PWR_CR_PLS_2V5 ((uint16_t)0x0060) /*!< PVD level 2.5V */ +#define PWR_CR_PLS_2V6 ((uint16_t)0x0080) /*!< PVD level 2.6V */ +#define PWR_CR_PLS_2V7 ((uint16_t)0x00A0) /*!< PVD level 2.7V */ +#define PWR_CR_PLS_2V8 ((uint16_t)0x00C0) /*!< PVD level 2.8V */ +#define PWR_CR_PLS_2V9 ((uint16_t)0x00E0) /*!< PVD level 2.9V */ + +#define PWR_CR_DBP ((uint16_t)0x0100) /*!< Disable Backup Domain write protection */ + + +/******************* Bit definition for PWR_CSR register ********************/ +#define PWR_CSR_WUF ((uint16_t)0x0001) /*!< Wakeup Flag */ +#define PWR_CSR_SBF ((uint16_t)0x0002) /*!< Standby Flag */ +#define PWR_CSR_PVDO ((uint16_t)0x0004) /*!< PVD Output */ +#define PWR_CSR_EWUP ((uint16_t)0x0100) /*!< Enable WKUP pin */ + +/******************************************************************************/ +/* */ +/* Backup registers */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for BKP_DR1 register ********************/ +#define BKP_DR1_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR2 register ********************/ +#define BKP_DR2_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR3 register ********************/ +#define BKP_DR3_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR4 register ********************/ +#define BKP_DR4_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR5 register ********************/ +#define BKP_DR5_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR6 register ********************/ +#define BKP_DR6_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR7 register ********************/ +#define BKP_DR7_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR8 register ********************/ +#define BKP_DR8_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR9 register ********************/ +#define BKP_DR9_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR10 register *******************/ +#define BKP_DR10_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR11 register *******************/ +#define BKP_DR11_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR12 register *******************/ +#define BKP_DR12_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR13 register *******************/ +#define BKP_DR13_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR14 register *******************/ +#define BKP_DR14_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR15 register *******************/ +#define BKP_DR15_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR16 register *******************/ +#define BKP_DR16_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR17 register *******************/ +#define BKP_DR17_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_DR18 register ********************/ +#define BKP_DR18_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR19 register *******************/ +#define BKP_DR19_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR20 register *******************/ +#define BKP_DR20_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR21 register *******************/ +#define BKP_DR21_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR22 register *******************/ +#define BKP_DR22_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR23 register *******************/ +#define BKP_DR23_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR24 register *******************/ +#define BKP_DR24_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR25 register *******************/ +#define BKP_DR25_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR26 register *******************/ +#define BKP_DR26_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR27 register *******************/ +#define BKP_DR27_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR28 register *******************/ +#define BKP_DR28_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR29 register *******************/ +#define BKP_DR29_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR30 register *******************/ +#define BKP_DR30_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR31 register *******************/ +#define BKP_DR31_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR32 register *******************/ +#define BKP_DR32_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR33 register *******************/ +#define BKP_DR33_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR34 register *******************/ +#define BKP_DR34_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR35 register *******************/ +#define BKP_DR35_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR36 register *******************/ +#define BKP_DR36_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR37 register *******************/ +#define BKP_DR37_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR38 register *******************/ +#define BKP_DR38_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR39 register *******************/ +#define BKP_DR39_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR40 register *******************/ +#define BKP_DR40_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR41 register *******************/ +#define BKP_DR41_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/******************* Bit definition for BKP_DR42 register *******************/ +#define BKP_DR42_D ((uint16_t)0xFFFF) /*!< Backup data */ + +/****************** Bit definition for BKP_RTCCR register *******************/ +#define BKP_RTCCR_CAL ((uint16_t)0x007F) /*!< Calibration value */ +#define BKP_RTCCR_CCO ((uint16_t)0x0080) /*!< Calibration Clock Output */ +#define BKP_RTCCR_ASOE ((uint16_t)0x0100) /*!< Alarm or Second Output Enable */ +#define BKP_RTCCR_ASOS ((uint16_t)0x0200) /*!< Alarm or Second Output Selection */ + +/******************** Bit definition for BKP_CR register ********************/ +#define BKP_CR_TPE ((uint8_t)0x01) /*!< TAMPER pin enable */ +#define BKP_CR_TPAL ((uint8_t)0x02) /*!< TAMPER pin active level */ + +/******************* Bit definition for BKP_CSR register ********************/ +#define BKP_CSR_CTE ((uint16_t)0x0001) /*!< Clear Tamper event */ +#define BKP_CSR_CTI ((uint16_t)0x0002) /*!< Clear Tamper Interrupt */ +#define BKP_CSR_TPIE ((uint16_t)0x0004) /*!< TAMPER Pin interrupt enable */ +#define BKP_CSR_TEF ((uint16_t)0x0100) /*!< Tamper Event Flag */ +#define BKP_CSR_TIF ((uint16_t)0x0200) /*!< Tamper Interrupt Flag */ + +/******************************************************************************/ +/* */ +/* Reset and Clock Control */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for RCC_CR register ********************/ +#define RCC_CR_HSION ((uint32_t)0x00000001) /*!< Internal High Speed clock enable */ +#define RCC_CR_HSIRDY ((uint32_t)0x00000002) /*!< Internal High Speed clock ready flag */ +#define RCC_CR_HSITRIM ((uint32_t)0x000000F8) /*!< Internal High Speed clock trimming */ +#define RCC_CR_HSICAL ((uint32_t)0x0000FF00) /*!< Internal High Speed clock Calibration */ +#define RCC_CR_HSEON ((uint32_t)0x00010000) /*!< External High Speed clock enable */ +#define RCC_CR_HSERDY ((uint32_t)0x00020000) /*!< External High Speed clock ready flag */ +#define RCC_CR_HSEBYP ((uint32_t)0x00040000) /*!< External High Speed clock Bypass */ +#define RCC_CR_CSSON ((uint32_t)0x00080000) /*!< Clock Security System enable */ +#define RCC_CR_PLLON ((uint32_t)0x01000000) /*!< PLL enable */ +#define RCC_CR_PLLRDY ((uint32_t)0x02000000) /*!< PLL clock ready flag */ + +#ifdef STM32F10X_CL + #define RCC_CR_PLL2ON ((uint32_t)0x04000000) /*!< PLL2 enable */ + #define RCC_CR_PLL2RDY ((uint32_t)0x08000000) /*!< PLL2 clock ready flag */ + #define RCC_CR_PLL3ON ((uint32_t)0x10000000) /*!< PLL3 enable */ + #define RCC_CR_PLL3RDY ((uint32_t)0x20000000) /*!< PLL3 clock ready flag */ +#endif /* STM32F10X_CL */ + +/******************* Bit definition for RCC_CFGR register *******************/ +/*!< SW configuration */ +#define RCC_CFGR_SW ((uint32_t)0x00000003) /*!< SW[1:0] bits (System clock Switch) */ +#define RCC_CFGR_SW_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define RCC_CFGR_SW_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define RCC_CFGR_SW_HSI ((uint32_t)0x00000000) /*!< HSI selected as system clock */ +#define RCC_CFGR_SW_HSE ((uint32_t)0x00000001) /*!< HSE selected as system clock */ +#define RCC_CFGR_SW_PLL ((uint32_t)0x00000002) /*!< PLL selected as system clock */ + +/*!< SWS configuration */ +#define RCC_CFGR_SWS ((uint32_t)0x0000000C) /*!< SWS[1:0] bits (System Clock Switch Status) */ +#define RCC_CFGR_SWS_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define RCC_CFGR_SWS_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define RCC_CFGR_SWS_HSI ((uint32_t)0x00000000) /*!< HSI oscillator used as system clock */ +#define RCC_CFGR_SWS_HSE ((uint32_t)0x00000004) /*!< HSE oscillator used as system clock */ +#define RCC_CFGR_SWS_PLL ((uint32_t)0x00000008) /*!< PLL used as system clock */ + +/*!< HPRE configuration */ +#define RCC_CFGR_HPRE ((uint32_t)0x000000F0) /*!< HPRE[3:0] bits (AHB prescaler) */ +#define RCC_CFGR_HPRE_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define RCC_CFGR_HPRE_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define RCC_CFGR_HPRE_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define RCC_CFGR_HPRE_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define RCC_CFGR_HPRE_DIV1 ((uint32_t)0x00000000) /*!< SYSCLK not divided */ +#define RCC_CFGR_HPRE_DIV2 ((uint32_t)0x00000080) /*!< SYSCLK divided by 2 */ +#define RCC_CFGR_HPRE_DIV4 ((uint32_t)0x00000090) /*!< SYSCLK divided by 4 */ +#define RCC_CFGR_HPRE_DIV8 ((uint32_t)0x000000A0) /*!< SYSCLK divided by 8 */ +#define RCC_CFGR_HPRE_DIV16 ((uint32_t)0x000000B0) /*!< SYSCLK divided by 16 */ +#define RCC_CFGR_HPRE_DIV64 ((uint32_t)0x000000C0) /*!< SYSCLK divided by 64 */ +#define RCC_CFGR_HPRE_DIV128 ((uint32_t)0x000000D0) /*!< SYSCLK divided by 128 */ +#define RCC_CFGR_HPRE_DIV256 ((uint32_t)0x000000E0) /*!< SYSCLK divided by 256 */ +#define RCC_CFGR_HPRE_DIV512 ((uint32_t)0x000000F0) /*!< SYSCLK divided by 512 */ + +/*!< PPRE1 configuration */ +#define RCC_CFGR_PPRE1 ((uint32_t)0x00000700) /*!< PRE1[2:0] bits (APB1 prescaler) */ +#define RCC_CFGR_PPRE1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_CFGR_PPRE1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define RCC_CFGR_PPRE1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE1_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE1_DIV2 ((uint32_t)0x00000400) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE1_DIV4 ((uint32_t)0x00000500) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE1_DIV8 ((uint32_t)0x00000600) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE1_DIV16 ((uint32_t)0x00000700) /*!< HCLK divided by 16 */ + +/*!< PPRE2 configuration */ +#define RCC_CFGR_PPRE2 ((uint32_t)0x00003800) /*!< PRE2[2:0] bits (APB2 prescaler) */ +#define RCC_CFGR_PPRE2_0 ((uint32_t)0x00000800) /*!< Bit 0 */ +#define RCC_CFGR_PPRE2_1 ((uint32_t)0x00001000) /*!< Bit 1 */ +#define RCC_CFGR_PPRE2_2 ((uint32_t)0x00002000) /*!< Bit 2 */ + +#define RCC_CFGR_PPRE2_DIV1 ((uint32_t)0x00000000) /*!< HCLK not divided */ +#define RCC_CFGR_PPRE2_DIV2 ((uint32_t)0x00002000) /*!< HCLK divided by 2 */ +#define RCC_CFGR_PPRE2_DIV4 ((uint32_t)0x00002800) /*!< HCLK divided by 4 */ +#define RCC_CFGR_PPRE2_DIV8 ((uint32_t)0x00003000) /*!< HCLK divided by 8 */ +#define RCC_CFGR_PPRE2_DIV16 ((uint32_t)0x00003800) /*!< HCLK divided by 16 */ + +/*!< ADCPPRE configuration */ +#define RCC_CFGR_ADCPRE ((uint32_t)0x0000C000) /*!< ADCPRE[1:0] bits (ADC prescaler) */ +#define RCC_CFGR_ADCPRE_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define RCC_CFGR_ADCPRE_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define RCC_CFGR_ADCPRE_DIV2 ((uint32_t)0x00000000) /*!< PCLK2 divided by 2 */ +#define RCC_CFGR_ADCPRE_DIV4 ((uint32_t)0x00004000) /*!< PCLK2 divided by 4 */ +#define RCC_CFGR_ADCPRE_DIV6 ((uint32_t)0x00008000) /*!< PCLK2 divided by 6 */ +#define RCC_CFGR_ADCPRE_DIV8 ((uint32_t)0x0000C000) /*!< PCLK2 divided by 8 */ + +#define RCC_CFGR_PLLSRC ((uint32_t)0x00010000) /*!< PLL entry clock source */ + +#define RCC_CFGR_PLLXTPRE ((uint32_t)0x00020000) /*!< HSE divider for PLL entry */ + +/*!< PLLMUL configuration */ +#define RCC_CFGR_PLLMULL ((uint32_t)0x003C0000) /*!< PLLMUL[3:0] bits (PLL multiplication factor) */ +#define RCC_CFGR_PLLMULL_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define RCC_CFGR_PLLMULL_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define RCC_CFGR_PLLMULL_2 ((uint32_t)0x00100000) /*!< Bit 2 */ +#define RCC_CFGR_PLLMULL_3 ((uint32_t)0x00200000) /*!< Bit 3 */ + +#ifdef STM32F10X_CL + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock * 4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock * 5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock * 6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock * 7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock * 8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock * 9 */ + #define RCC_CFGR_PLLMULL6_5 ((uint32_t)0x00340000) /*!< PLL input clock * 6.5 */ + + #define RCC_CFGR_OTGFSPRE ((uint32_t)0x00400000) /*!< USB OTG FS prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x0F000000) /*!< MCO[3:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + #define RCC_CFGR_MCO_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLLCLK_Div2 ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ + #define RCC_CFGR_MCO_PLL2CLK ((uint32_t)0x08000000) /*!< PLL2 clock selected as MCO source*/ + #define RCC_CFGR_MCO_PLL3CLK_Div2 ((uint32_t)0x09000000) /*!< PLL3 clock divided by 2 selected as MCO source*/ + #define RCC_CFGR_MCO_Ext_HSE ((uint32_t)0x0A000000) /*!< XT1 external 3-25 MHz oscillator clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL3CLK ((uint32_t)0x0B000000) /*!< PLL3 clock selected as MCO source */ +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_PREDIV1 ((uint32_t)0x00010000) /*!< PREDIV1 clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_PREDIV1 ((uint32_t)0x00000000) /*!< PREDIV1 clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_PREDIV1_Div2 ((uint32_t)0x00020000) /*!< PREDIV1 clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#else + #define RCC_CFGR_PLLSRC_HSI_Div2 ((uint32_t)0x00000000) /*!< HSI clock divided by 2 selected as PLL entry clock source */ + #define RCC_CFGR_PLLSRC_HSE ((uint32_t)0x00010000) /*!< HSE clock selected as PLL entry clock source */ + + #define RCC_CFGR_PLLXTPRE_HSE ((uint32_t)0x00000000) /*!< HSE clock not divided for PLL entry */ + #define RCC_CFGR_PLLXTPRE_HSE_Div2 ((uint32_t)0x00020000) /*!< HSE clock divided by 2 for PLL entry */ + + #define RCC_CFGR_PLLMULL2 ((uint32_t)0x00000000) /*!< PLL input clock*2 */ + #define RCC_CFGR_PLLMULL3 ((uint32_t)0x00040000) /*!< PLL input clock*3 */ + #define RCC_CFGR_PLLMULL4 ((uint32_t)0x00080000) /*!< PLL input clock*4 */ + #define RCC_CFGR_PLLMULL5 ((uint32_t)0x000C0000) /*!< PLL input clock*5 */ + #define RCC_CFGR_PLLMULL6 ((uint32_t)0x00100000) /*!< PLL input clock*6 */ + #define RCC_CFGR_PLLMULL7 ((uint32_t)0x00140000) /*!< PLL input clock*7 */ + #define RCC_CFGR_PLLMULL8 ((uint32_t)0x00180000) /*!< PLL input clock*8 */ + #define RCC_CFGR_PLLMULL9 ((uint32_t)0x001C0000) /*!< PLL input clock*9 */ + #define RCC_CFGR_PLLMULL10 ((uint32_t)0x00200000) /*!< PLL input clock10 */ + #define RCC_CFGR_PLLMULL11 ((uint32_t)0x00240000) /*!< PLL input clock*11 */ + #define RCC_CFGR_PLLMULL12 ((uint32_t)0x00280000) /*!< PLL input clock*12 */ + #define RCC_CFGR_PLLMULL13 ((uint32_t)0x002C0000) /*!< PLL input clock*13 */ + #define RCC_CFGR_PLLMULL14 ((uint32_t)0x00300000) /*!< PLL input clock*14 */ + #define RCC_CFGR_PLLMULL15 ((uint32_t)0x00340000) /*!< PLL input clock*15 */ + #define RCC_CFGR_PLLMULL16 ((uint32_t)0x00380000) /*!< PLL input clock*16 */ + #define RCC_CFGR_USBPRE ((uint32_t)0x00400000) /*!< USB Device prescaler */ + +/*!< MCO configuration */ + #define RCC_CFGR_MCO ((uint32_t)0x07000000) /*!< MCO[2:0] bits (Microcontroller Clock Output) */ + #define RCC_CFGR_MCO_0 ((uint32_t)0x01000000) /*!< Bit 0 */ + #define RCC_CFGR_MCO_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + #define RCC_CFGR_MCO_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + + #define RCC_CFGR_MCO_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ + #define RCC_CFGR_MCO_SYSCLK ((uint32_t)0x04000000) /*!< System clock selected as MCO source */ + #define RCC_CFGR_MCO_HSI ((uint32_t)0x05000000) /*!< HSI clock selected as MCO source */ + #define RCC_CFGR_MCO_HSE ((uint32_t)0x06000000) /*!< HSE clock selected as MCO source */ + #define RCC_CFGR_MCO_PLL ((uint32_t)0x07000000) /*!< PLL clock divided by 2 selected as MCO source */ +#endif /* STM32F10X_CL */ + +/*!<****************** Bit definition for RCC_CIR register ********************/ +#define RCC_CIR_LSIRDYF ((uint32_t)0x00000001) /*!< LSI Ready Interrupt flag */ +#define RCC_CIR_LSERDYF ((uint32_t)0x00000002) /*!< LSE Ready Interrupt flag */ +#define RCC_CIR_HSIRDYF ((uint32_t)0x00000004) /*!< HSI Ready Interrupt flag */ +#define RCC_CIR_HSERDYF ((uint32_t)0x00000008) /*!< HSE Ready Interrupt flag */ +#define RCC_CIR_PLLRDYF ((uint32_t)0x00000010) /*!< PLL Ready Interrupt flag */ +#define RCC_CIR_CSSF ((uint32_t)0x00000080) /*!< Clock Security System Interrupt flag */ +#define RCC_CIR_LSIRDYIE ((uint32_t)0x00000100) /*!< LSI Ready Interrupt Enable */ +#define RCC_CIR_LSERDYIE ((uint32_t)0x00000200) /*!< LSE Ready Interrupt Enable */ +#define RCC_CIR_HSIRDYIE ((uint32_t)0x00000400) /*!< HSI Ready Interrupt Enable */ +#define RCC_CIR_HSERDYIE ((uint32_t)0x00000800) /*!< HSE Ready Interrupt Enable */ +#define RCC_CIR_PLLRDYIE ((uint32_t)0x00001000) /*!< PLL Ready Interrupt Enable */ +#define RCC_CIR_LSIRDYC ((uint32_t)0x00010000) /*!< LSI Ready Interrupt Clear */ +#define RCC_CIR_LSERDYC ((uint32_t)0x00020000) /*!< LSE Ready Interrupt Clear */ +#define RCC_CIR_HSIRDYC ((uint32_t)0x00040000) /*!< HSI Ready Interrupt Clear */ +#define RCC_CIR_HSERDYC ((uint32_t)0x00080000) /*!< HSE Ready Interrupt Clear */ +#define RCC_CIR_PLLRDYC ((uint32_t)0x00100000) /*!< PLL Ready Interrupt Clear */ +#define RCC_CIR_CSSC ((uint32_t)0x00800000) /*!< Clock Security System Interrupt Clear */ + +#ifdef STM32F10X_CL + #define RCC_CIR_PLL2RDYF ((uint32_t)0x00000020) /*!< PLL2 Ready Interrupt flag */ + #define RCC_CIR_PLL3RDYF ((uint32_t)0x00000040) /*!< PLL3 Ready Interrupt flag */ + #define RCC_CIR_PLL2RDYIE ((uint32_t)0x00002000) /*!< PLL2 Ready Interrupt Enable */ + #define RCC_CIR_PLL3RDYIE ((uint32_t)0x00004000) /*!< PLL3 Ready Interrupt Enable */ + #define RCC_CIR_PLL2RDYC ((uint32_t)0x00200000) /*!< PLL2 Ready Interrupt Clear */ + #define RCC_CIR_PLL3RDYC ((uint32_t)0x00400000) /*!< PLL3 Ready Interrupt Clear */ +#endif /* STM32F10X_CL */ + +/***************** Bit definition for RCC_APB2RSTR register *****************/ +#define RCC_APB2RSTR_AFIORST ((uint32_t)0x00000001) /*!< Alternate Function I/O reset */ +#define RCC_APB2RSTR_IOPARST ((uint32_t)0x00000004) /*!< I/O port A reset */ +#define RCC_APB2RSTR_IOPBRST ((uint32_t)0x00000008) /*!< I/O port B reset */ +#define RCC_APB2RSTR_IOPCRST ((uint32_t)0x00000010) /*!< I/O port C reset */ +#define RCC_APB2RSTR_IOPDRST ((uint32_t)0x00000020) /*!< I/O port D reset */ +#define RCC_APB2RSTR_ADC1RST ((uint32_t)0x00000200) /*!< ADC 1 interface reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_ADC2RST ((uint32_t)0x00000400) /*!< ADC 2 interface reset */ +#endif + +#define RCC_APB2RSTR_TIM1RST ((uint32_t)0x00000800) /*!< TIM1 Timer reset */ +#define RCC_APB2RSTR_SPI1RST ((uint32_t)0x00001000) /*!< SPI 1 reset */ +#define RCC_APB2RSTR_USART1RST ((uint32_t)0x00004000) /*!< USART1 reset */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2RSTR_TIM15RST ((uint32_t)0x00010000) /*!< TIM15 Timer reset */ +#define RCC_APB2RSTR_TIM16RST ((uint32_t)0x00020000) /*!< TIM16 Timer reset */ +#define RCC_APB2RSTR_TIM17RST ((uint32_t)0x00040000) /*!< TIM17 Timer reset */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2RSTR_IOPERST ((uint32_t)0x00000040) /*!< I/O port E reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ + #define RCC_APB2RSTR_TIM8RST ((uint32_t)0x00002000) /*!< TIM8 Timer reset */ + #define RCC_APB2RSTR_ADC3RST ((uint32_t)0x00008000) /*!< ADC3 interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2RSTR_IOPFRST ((uint32_t)0x00000080) /*!< I/O port F reset */ + #define RCC_APB2RSTR_IOPGRST ((uint32_t)0x00000100) /*!< I/O port G reset */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2RSTR_TIM9RST ((uint32_t)0x00080000) /*!< TIM9 Timer reset */ + #define RCC_APB2RSTR_TIM10RST ((uint32_t)0x00100000) /*!< TIM10 Timer reset */ + #define RCC_APB2RSTR_TIM11RST ((uint32_t)0x00200000) /*!< TIM11 Timer reset */ +#endif /* STM32F10X_XL */ + +/***************** Bit definition for RCC_APB1RSTR register *****************/ +#define RCC_APB1RSTR_TIM2RST ((uint32_t)0x00000001) /*!< Timer 2 reset */ +#define RCC_APB1RSTR_TIM3RST ((uint32_t)0x00000002) /*!< Timer 3 reset */ +#define RCC_APB1RSTR_WWDGRST ((uint32_t)0x00000800) /*!< Window Watchdog reset */ +#define RCC_APB1RSTR_USART2RST ((uint32_t)0x00020000) /*!< USART 2 reset */ +#define RCC_APB1RSTR_I2C1RST ((uint32_t)0x00200000) /*!< I2C 1 reset */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1RSTR_CAN1RST ((uint32_t)0x02000000) /*!< CAN1 reset */ +#endif + +#define RCC_APB1RSTR_BKPRST ((uint32_t)0x08000000) /*!< Backup interface reset */ +#define RCC_APB1RSTR_PWRRST ((uint32_t)0x10000000) /*!< Power interface reset */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1RSTR_TIM4RST ((uint32_t)0x00000004) /*!< Timer 4 reset */ + #define RCC_APB1RSTR_SPI2RST ((uint32_t)0x00004000) /*!< SPI 2 reset */ + #define RCC_APB1RSTR_USART3RST ((uint32_t)0x00040000) /*!< USART 3 reset */ + #define RCC_APB1RSTR_I2C2RST ((uint32_t)0x00400000) /*!< I2C 2 reset */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_USBRST ((uint32_t)0x00800000) /*!< USB Device reset */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_XL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM6RST ((uint32_t)0x00000010) /*!< Timer 6 reset */ + #define RCC_APB1RSTR_TIM7RST ((uint32_t)0x00000020) /*!< Timer 7 reset */ + #define RCC_APB1RSTR_DACRST ((uint32_t)0x20000000) /*!< DAC interface reset */ + #define RCC_APB1RSTR_CECRST ((uint32_t)0x40000000) /*!< CEC interface reset */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB1RSTR_TIM5RST ((uint32_t)0x00000008) /*!< Timer 5 reset */ + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ + #define RCC_APB1RSTR_SPI3RST ((uint32_t)0x00008000) /*!< SPI 3 reset */ + #define RCC_APB1RSTR_UART4RST ((uint32_t)0x00080000) /*!< UART 4 reset */ + #define RCC_APB1RSTR_UART5RST ((uint32_t)0x00100000) /*!< UART 5 reset */ +#endif + +#ifdef STM32F10X_CL + #define RCC_APB1RSTR_CAN2RST ((uint32_t)0x04000000) /*!< CAN2 reset */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1RSTR_TIM12RST ((uint32_t)0x00000040) /*!< TIM12 Timer reset */ + #define RCC_APB1RSTR_TIM13RST ((uint32_t)0x00000080) /*!< TIM13 Timer reset */ + #define RCC_APB1RSTR_TIM14RST ((uint32_t)0x00000100) /*!< TIM14 Timer reset */ +#endif /* STM32F10X_XL */ + +/****************** Bit definition for RCC_AHBENR register ******************/ +#define RCC_AHBENR_DMA1EN ((uint16_t)0x0001) /*!< DMA1 clock enable */ +#define RCC_AHBENR_SRAMEN ((uint16_t)0x0004) /*!< SRAM interface clock enable */ +#define RCC_AHBENR_FLITFEN ((uint16_t)0x0010) /*!< FLITF clock enable */ +#define RCC_AHBENR_CRCEN ((uint16_t)0x0040) /*!< CRC clock enable */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) || defined (STM32F10X_HD_VL) + #define RCC_AHBENR_DMA2EN ((uint16_t)0x0002) /*!< DMA2 clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ + #define RCC_AHBENR_SDIOEN ((uint16_t)0x0400) /*!< SDIO clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_AHBENR_FSMCEN ((uint16_t)0x0100) /*!< FSMC clock enable */ +#endif + +#ifdef STM32F10X_CL + #define RCC_AHBENR_OTGFSEN ((uint32_t)0x00001000) /*!< USB OTG FS clock enable */ + #define RCC_AHBENR_ETHMACEN ((uint32_t)0x00004000) /*!< ETHERNET MAC clock enable */ + #define RCC_AHBENR_ETHMACTXEN ((uint32_t)0x00008000) /*!< ETHERNET MAC Tx clock enable */ + #define RCC_AHBENR_ETHMACRXEN ((uint32_t)0x00010000) /*!< ETHERNET MAC Rx clock enable */ +#endif /* STM32F10X_CL */ + +/****************** Bit definition for RCC_APB2ENR register *****************/ +#define RCC_APB2ENR_AFIOEN ((uint32_t)0x00000001) /*!< Alternate Function I/O clock enable */ +#define RCC_APB2ENR_IOPAEN ((uint32_t)0x00000004) /*!< I/O port A clock enable */ +#define RCC_APB2ENR_IOPBEN ((uint32_t)0x00000008) /*!< I/O port B clock enable */ +#define RCC_APB2ENR_IOPCEN ((uint32_t)0x00000010) /*!< I/O port C clock enable */ +#define RCC_APB2ENR_IOPDEN ((uint32_t)0x00000020) /*!< I/O port D clock enable */ +#define RCC_APB2ENR_ADC1EN ((uint32_t)0x00000200) /*!< ADC 1 interface clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_ADC2EN ((uint32_t)0x00000400) /*!< ADC 2 interface clock enable */ +#endif + +#define RCC_APB2ENR_TIM1EN ((uint32_t)0x00000800) /*!< TIM1 Timer clock enable */ +#define RCC_APB2ENR_SPI1EN ((uint32_t)0x00001000) /*!< SPI 1 clock enable */ +#define RCC_APB2ENR_USART1EN ((uint32_t)0x00004000) /*!< USART1 clock enable */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +#define RCC_APB2ENR_TIM15EN ((uint32_t)0x00010000) /*!< TIM15 Timer clock enable */ +#define RCC_APB2ENR_TIM16EN ((uint32_t)0x00020000) /*!< TIM16 Timer clock enable */ +#define RCC_APB2ENR_TIM17EN ((uint32_t)0x00040000) /*!< TIM17 Timer clock enable */ +#endif + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB2ENR_IOPEEN ((uint32_t)0x00000040) /*!< I/O port E clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ + #define RCC_APB2ENR_TIM8EN ((uint32_t)0x00002000) /*!< TIM8 Timer clock enable */ + #define RCC_APB2ENR_ADC3EN ((uint32_t)0x00008000) /*!< DMA1 clock enable */ +#endif + +#if defined (STM32F10X_HD_VL) + #define RCC_APB2ENR_IOPFEN ((uint32_t)0x00000080) /*!< I/O port F clock enable */ + #define RCC_APB2ENR_IOPGEN ((uint32_t)0x00000100) /*!< I/O port G clock enable */ +#endif + +#ifdef STM32F10X_XL + #define RCC_APB2ENR_TIM9EN ((uint32_t)0x00080000) /*!< TIM9 Timer clock enable */ + #define RCC_APB2ENR_TIM10EN ((uint32_t)0x00100000) /*!< TIM10 Timer clock enable */ + #define RCC_APB2ENR_TIM11EN ((uint32_t)0x00200000) /*!< TIM11 Timer clock enable */ +#endif + +/***************** Bit definition for RCC_APB1ENR register ******************/ +#define RCC_APB1ENR_TIM2EN ((uint32_t)0x00000001) /*!< Timer 2 clock enabled*/ +#define RCC_APB1ENR_TIM3EN ((uint32_t)0x00000002) /*!< Timer 3 clock enable */ +#define RCC_APB1ENR_WWDGEN ((uint32_t)0x00000800) /*!< Window Watchdog clock enable */ +#define RCC_APB1ENR_USART2EN ((uint32_t)0x00020000) /*!< USART 2 clock enable */ +#define RCC_APB1ENR_I2C1EN ((uint32_t)0x00200000) /*!< I2C 1 clock enable */ + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) +#define RCC_APB1ENR_CAN1EN ((uint32_t)0x02000000) /*!< CAN1 clock enable */ +#endif + +#define RCC_APB1ENR_BKPEN ((uint32_t)0x08000000) /*!< Backup interface clock enable */ +#define RCC_APB1ENR_PWREN ((uint32_t)0x10000000) /*!< Power interface clock enable */ + +#if !defined (STM32F10X_LD) && !defined (STM32F10X_LD_VL) + #define RCC_APB1ENR_TIM4EN ((uint32_t)0x00000004) /*!< Timer 4 clock enable */ + #define RCC_APB1ENR_SPI2EN ((uint32_t)0x00004000) /*!< SPI 2 clock enable */ + #define RCC_APB1ENR_USART3EN ((uint32_t)0x00040000) /*!< USART 3 clock enable */ + #define RCC_APB1ENR_I2C2EN ((uint32_t)0x00400000) /*!< I2C 2 clock enable */ +#endif /* STM32F10X_LD && STM32F10X_LD_VL */ + +#if defined (STM32F10X_HD) || defined (STM32F10X_MD) || defined (STM32F10X_LD) + #define RCC_APB1ENR_USBEN ((uint32_t)0x00800000) /*!< USB Device clock enable */ +#endif + +#if defined (STM32F10X_HD) || defined (STM32F10X_CL) + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ +#endif + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + #define RCC_APB1ENR_TIM6EN ((uint32_t)0x00000010) /*!< Timer 6 clock enable */ + #define RCC_APB1ENR_TIM7EN ((uint32_t)0x00000020) /*!< Timer 7 clock enable */ + #define RCC_APB1ENR_DACEN ((uint32_t)0x20000000) /*!< DAC interface clock enable */ + #define RCC_APB1ENR_CECEN ((uint32_t)0x40000000) /*!< CEC interface clock enable */ +#endif + +#ifdef STM32F10X_HD_VL + #define RCC_APB1ENR_TIM5EN ((uint32_t)0x00000008) /*!< Timer 5 clock enable */ + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ + #define RCC_APB1ENR_SPI3EN ((uint32_t)0x00008000) /*!< SPI 3 clock enable */ + #define RCC_APB1ENR_UART4EN ((uint32_t)0x00080000) /*!< UART 4 clock enable */ + #define RCC_APB1ENR_UART5EN ((uint32_t)0x00100000) /*!< UART 5 clock enable */ +#endif /* STM32F10X_HD_VL */ + +#ifdef STM32F10X_CL + #define RCC_APB1ENR_CAN2EN ((uint32_t)0x04000000) /*!< CAN2 clock enable */ +#endif /* STM32F10X_CL */ + +#ifdef STM32F10X_XL + #define RCC_APB1ENR_TIM12EN ((uint32_t)0x00000040) /*!< TIM12 Timer clock enable */ + #define RCC_APB1ENR_TIM13EN ((uint32_t)0x00000080) /*!< TIM13 Timer clock enable */ + #define RCC_APB1ENR_TIM14EN ((uint32_t)0x00000100) /*!< TIM14 Timer clock enable */ +#endif /* STM32F10X_XL */ + +/******************* Bit definition for RCC_BDCR register *******************/ +#define RCC_BDCR_LSEON ((uint32_t)0x00000001) /*!< External Low Speed oscillator enable */ +#define RCC_BDCR_LSERDY ((uint32_t)0x00000002) /*!< External Low Speed oscillator Ready */ +#define RCC_BDCR_LSEBYP ((uint32_t)0x00000004) /*!< External Low Speed oscillator Bypass */ + +#define RCC_BDCR_RTCSEL ((uint32_t)0x00000300) /*!< RTCSEL[1:0] bits (RTC clock source selection) */ +#define RCC_BDCR_RTCSEL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define RCC_BDCR_RTCSEL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< RTC congiguration */ +#define RCC_BDCR_RTCSEL_NOCLOCK ((uint32_t)0x00000000) /*!< No clock */ +#define RCC_BDCR_RTCSEL_LSE ((uint32_t)0x00000100) /*!< LSE oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_LSI ((uint32_t)0x00000200) /*!< LSI oscillator clock used as RTC clock */ +#define RCC_BDCR_RTCSEL_HSE ((uint32_t)0x00000300) /*!< HSE oscillator clock divided by 128 used as RTC clock */ + +#define RCC_BDCR_RTCEN ((uint32_t)0x00008000) /*!< RTC clock enable */ +#define RCC_BDCR_BDRST ((uint32_t)0x00010000) /*!< Backup domain software reset */ + +/******************* Bit definition for RCC_CSR register ********************/ +#define RCC_CSR_LSION ((uint32_t)0x00000001) /*!< Internal Low Speed oscillator enable */ +#define RCC_CSR_LSIRDY ((uint32_t)0x00000002) /*!< Internal Low Speed oscillator Ready */ +#define RCC_CSR_RMVF ((uint32_t)0x01000000) /*!< Remove reset flag */ +#define RCC_CSR_PINRSTF ((uint32_t)0x04000000) /*!< PIN reset flag */ +#define RCC_CSR_PORRSTF ((uint32_t)0x08000000) /*!< POR/PDR reset flag */ +#define RCC_CSR_SFTRSTF ((uint32_t)0x10000000) /*!< Software Reset flag */ +#define RCC_CSR_IWDGRSTF ((uint32_t)0x20000000) /*!< Independent Watchdog reset flag */ +#define RCC_CSR_WWDGRSTF ((uint32_t)0x40000000) /*!< Window watchdog reset flag */ +#define RCC_CSR_LPWRRSTF ((uint32_t)0x80000000) /*!< Low-Power reset flag */ + +#ifdef STM32F10X_CL +/******************* Bit definition for RCC_AHBRSTR register ****************/ + #define RCC_AHBRSTR_OTGFSRST ((uint32_t)0x00001000) /*!< USB OTG FS reset */ + #define RCC_AHBRSTR_ETHMACRST ((uint32_t)0x00004000) /*!< ETHERNET MAC reset */ + +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ + +/*!< PREDIV2 configuration */ + #define RCC_CFGR2_PREDIV2 ((uint32_t)0x000000F0) /*!< PREDIV2[3:0] bits */ + #define RCC_CFGR2_PREDIV2_0 ((uint32_t)0x00000010) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV2_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV2_2 ((uint32_t)0x00000040) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV2_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV2_DIV1 ((uint32_t)0x00000000) /*!< PREDIV2 input clock not divided */ + #define RCC_CFGR2_PREDIV2_DIV2 ((uint32_t)0x00000010) /*!< PREDIV2 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV2_DIV3 ((uint32_t)0x00000020) /*!< PREDIV2 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV2_DIV4 ((uint32_t)0x00000030) /*!< PREDIV2 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV2_DIV5 ((uint32_t)0x00000040) /*!< PREDIV2 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV2_DIV6 ((uint32_t)0x00000050) /*!< PREDIV2 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV2_DIV7 ((uint32_t)0x00000060) /*!< PREDIV2 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV2_DIV8 ((uint32_t)0x00000070) /*!< PREDIV2 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV2_DIV9 ((uint32_t)0x00000080) /*!< PREDIV2 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV2_DIV10 ((uint32_t)0x00000090) /*!< PREDIV2 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV2_DIV11 ((uint32_t)0x000000A0) /*!< PREDIV2 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV2_DIV12 ((uint32_t)0x000000B0) /*!< PREDIV2 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV2_DIV13 ((uint32_t)0x000000C0) /*!< PREDIV2 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV2_DIV14 ((uint32_t)0x000000D0) /*!< PREDIV2 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV2_DIV15 ((uint32_t)0x000000E0) /*!< PREDIV2 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV2_DIV16 ((uint32_t)0x000000F0) /*!< PREDIV2 input clock divided by 16 */ + +/*!< PLL2MUL configuration */ + #define RCC_CFGR2_PLL2MUL ((uint32_t)0x00000F00) /*!< PLL2MUL[3:0] bits */ + #define RCC_CFGR2_PLL2MUL_0 ((uint32_t)0x00000100) /*!< Bit 0 */ + #define RCC_CFGR2_PLL2MUL_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + #define RCC_CFGR2_PLL2MUL_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + #define RCC_CFGR2_PLL2MUL_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL2MUL8 ((uint32_t)0x00000600) /*!< PLL2 input clock * 8 */ + #define RCC_CFGR2_PLL2MUL9 ((uint32_t)0x00000700) /*!< PLL2 input clock * 9 */ + #define RCC_CFGR2_PLL2MUL10 ((uint32_t)0x00000800) /*!< PLL2 input clock * 10 */ + #define RCC_CFGR2_PLL2MUL11 ((uint32_t)0x00000900) /*!< PLL2 input clock * 11 */ + #define RCC_CFGR2_PLL2MUL12 ((uint32_t)0x00000A00) /*!< PLL2 input clock * 12 */ + #define RCC_CFGR2_PLL2MUL13 ((uint32_t)0x00000B00) /*!< PLL2 input clock * 13 */ + #define RCC_CFGR2_PLL2MUL14 ((uint32_t)0x00000C00) /*!< PLL2 input clock * 14 */ + #define RCC_CFGR2_PLL2MUL16 ((uint32_t)0x00000E00) /*!< PLL2 input clock * 16 */ + #define RCC_CFGR2_PLL2MUL20 ((uint32_t)0x00000F00) /*!< PLL2 input clock * 20 */ + +/*!< PLL3MUL configuration */ + #define RCC_CFGR2_PLL3MUL ((uint32_t)0x0000F000) /*!< PLL3MUL[3:0] bits */ + #define RCC_CFGR2_PLL3MUL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ + #define RCC_CFGR2_PLL3MUL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + #define RCC_CFGR2_PLL3MUL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + #define RCC_CFGR2_PLL3MUL_3 ((uint32_t)0x00008000) /*!< Bit 3 */ + + #define RCC_CFGR2_PLL3MUL8 ((uint32_t)0x00006000) /*!< PLL3 input clock * 8 */ + #define RCC_CFGR2_PLL3MUL9 ((uint32_t)0x00007000) /*!< PLL3 input clock * 9 */ + #define RCC_CFGR2_PLL3MUL10 ((uint32_t)0x00008000) /*!< PLL3 input clock * 10 */ + #define RCC_CFGR2_PLL3MUL11 ((uint32_t)0x00009000) /*!< PLL3 input clock * 11 */ + #define RCC_CFGR2_PLL3MUL12 ((uint32_t)0x0000A000) /*!< PLL3 input clock * 12 */ + #define RCC_CFGR2_PLL3MUL13 ((uint32_t)0x0000B000) /*!< PLL3 input clock * 13 */ + #define RCC_CFGR2_PLL3MUL14 ((uint32_t)0x0000C000) /*!< PLL3 input clock * 14 */ + #define RCC_CFGR2_PLL3MUL16 ((uint32_t)0x0000E000) /*!< PLL3 input clock * 16 */ + #define RCC_CFGR2_PLL3MUL20 ((uint32_t)0x0000F000) /*!< PLL3 input clock * 20 */ + + #define RCC_CFGR2_PREDIV1SRC ((uint32_t)0x00010000) /*!< PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_PLL2 ((uint32_t)0x00010000) /*!< PLL2 selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_PREDIV1SRC_HSE ((uint32_t)0x00000000) /*!< HSE selected as PREDIV1 entry clock source */ + #define RCC_CFGR2_I2S2SRC ((uint32_t)0x00020000) /*!< I2S2 entry clock source */ + #define RCC_CFGR2_I2S3SRC ((uint32_t)0x00040000) /*!< I2S3 clock source */ +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/******************* Bit definition for RCC_CFGR2 register ******************/ +/*!< PREDIV1 configuration */ + #define RCC_CFGR2_PREDIV1 ((uint32_t)0x0000000F) /*!< PREDIV1[3:0] bits */ + #define RCC_CFGR2_PREDIV1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ + #define RCC_CFGR2_PREDIV1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + #define RCC_CFGR2_PREDIV1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + #define RCC_CFGR2_PREDIV1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + + #define RCC_CFGR2_PREDIV1_DIV1 ((uint32_t)0x00000000) /*!< PREDIV1 input clock not divided */ + #define RCC_CFGR2_PREDIV1_DIV2 ((uint32_t)0x00000001) /*!< PREDIV1 input clock divided by 2 */ + #define RCC_CFGR2_PREDIV1_DIV3 ((uint32_t)0x00000002) /*!< PREDIV1 input clock divided by 3 */ + #define RCC_CFGR2_PREDIV1_DIV4 ((uint32_t)0x00000003) /*!< PREDIV1 input clock divided by 4 */ + #define RCC_CFGR2_PREDIV1_DIV5 ((uint32_t)0x00000004) /*!< PREDIV1 input clock divided by 5 */ + #define RCC_CFGR2_PREDIV1_DIV6 ((uint32_t)0x00000005) /*!< PREDIV1 input clock divided by 6 */ + #define RCC_CFGR2_PREDIV1_DIV7 ((uint32_t)0x00000006) /*!< PREDIV1 input clock divided by 7 */ + #define RCC_CFGR2_PREDIV1_DIV8 ((uint32_t)0x00000007) /*!< PREDIV1 input clock divided by 8 */ + #define RCC_CFGR2_PREDIV1_DIV9 ((uint32_t)0x00000008) /*!< PREDIV1 input clock divided by 9 */ + #define RCC_CFGR2_PREDIV1_DIV10 ((uint32_t)0x00000009) /*!< PREDIV1 input clock divided by 10 */ + #define RCC_CFGR2_PREDIV1_DIV11 ((uint32_t)0x0000000A) /*!< PREDIV1 input clock divided by 11 */ + #define RCC_CFGR2_PREDIV1_DIV12 ((uint32_t)0x0000000B) /*!< PREDIV1 input clock divided by 12 */ + #define RCC_CFGR2_PREDIV1_DIV13 ((uint32_t)0x0000000C) /*!< PREDIV1 input clock divided by 13 */ + #define RCC_CFGR2_PREDIV1_DIV14 ((uint32_t)0x0000000D) /*!< PREDIV1 input clock divided by 14 */ + #define RCC_CFGR2_PREDIV1_DIV15 ((uint32_t)0x0000000E) /*!< PREDIV1 input clock divided by 15 */ + #define RCC_CFGR2_PREDIV1_DIV16 ((uint32_t)0x0000000F) /*!< PREDIV1 input clock divided by 16 */ +#endif + +/******************************************************************************/ +/* */ +/* General Purpose and Alternate Function I/O */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for GPIO_CRL register *******************/ +#define GPIO_CRL_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRL_MODE0 ((uint32_t)0x00000003) /*!< MODE0[1:0] bits (Port x mode bits, pin 0) */ +#define GPIO_CRL_MODE0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRL_MODE0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRL_MODE1 ((uint32_t)0x00000030) /*!< MODE1[1:0] bits (Port x mode bits, pin 1) */ +#define GPIO_CRL_MODE1_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRL_MODE1_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRL_MODE2 ((uint32_t)0x00000300) /*!< MODE2[1:0] bits (Port x mode bits, pin 2) */ +#define GPIO_CRL_MODE2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRL_MODE2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRL_MODE3 ((uint32_t)0x00003000) /*!< MODE3[1:0] bits (Port x mode bits, pin 3) */ +#define GPIO_CRL_MODE3_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRL_MODE3_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE4 ((uint32_t)0x00030000) /*!< MODE4[1:0] bits (Port x mode bits, pin 4) */ +#define GPIO_CRL_MODE4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRL_MODE4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE5 ((uint32_t)0x00300000) /*!< MODE5[1:0] bits (Port x mode bits, pin 5) */ +#define GPIO_CRL_MODE5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRL_MODE5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE6 ((uint32_t)0x03000000) /*!< MODE6[1:0] bits (Port x mode bits, pin 6) */ +#define GPIO_CRL_MODE6_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE6_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRL_MODE7 ((uint32_t)0x30000000) /*!< MODE7[1:0] bits (Port x mode bits, pin 7) */ +#define GPIO_CRL_MODE7_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRL_MODE7_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRL_CNF0 ((uint32_t)0x0000000C) /*!< CNF0[1:0] bits (Port x configuration bits, pin 0) */ +#define GPIO_CRL_CNF0_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRL_CNF0_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRL_CNF1 ((uint32_t)0x000000C0) /*!< CNF1[1:0] bits (Port x configuration bits, pin 1) */ +#define GPIO_CRL_CNF1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRL_CNF1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRL_CNF2 ((uint32_t)0x00000C00) /*!< CNF2[1:0] bits (Port x configuration bits, pin 2) */ +#define GPIO_CRL_CNF2_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRL_CNF2_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRL_CNF3 ((uint32_t)0x0000C000) /*!< CNF3[1:0] bits (Port x configuration bits, pin 3) */ +#define GPIO_CRL_CNF3_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRL_CNF3_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF4 ((uint32_t)0x000C0000) /*!< CNF4[1:0] bits (Port x configuration bits, pin 4) */ +#define GPIO_CRL_CNF4_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRL_CNF4_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF5 ((uint32_t)0x00C00000) /*!< CNF5[1:0] bits (Port x configuration bits, pin 5) */ +#define GPIO_CRL_CNF5_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRL_CNF5_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF6 ((uint32_t)0x0C000000) /*!< CNF6[1:0] bits (Port x configuration bits, pin 6) */ +#define GPIO_CRL_CNF6_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF6_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRL_CNF7 ((uint32_t)0xC0000000) /*!< CNF7[1:0] bits (Port x configuration bits, pin 7) */ +#define GPIO_CRL_CNF7_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRL_CNF7_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/******************* Bit definition for GPIO_CRH register *******************/ +#define GPIO_CRH_MODE ((uint32_t)0x33333333) /*!< Port x mode bits */ + +#define GPIO_CRH_MODE8 ((uint32_t)0x00000003) /*!< MODE8[1:0] bits (Port x mode bits, pin 8) */ +#define GPIO_CRH_MODE8_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define GPIO_CRH_MODE8_1 ((uint32_t)0x00000002) /*!< Bit 1 */ + +#define GPIO_CRH_MODE9 ((uint32_t)0x00000030) /*!< MODE9[1:0] bits (Port x mode bits, pin 9) */ +#define GPIO_CRH_MODE9_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define GPIO_CRH_MODE9_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define GPIO_CRH_MODE10 ((uint32_t)0x00000300) /*!< MODE10[1:0] bits (Port x mode bits, pin 10) */ +#define GPIO_CRH_MODE10_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define GPIO_CRH_MODE10_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +#define GPIO_CRH_MODE11 ((uint32_t)0x00003000) /*!< MODE11[1:0] bits (Port x mode bits, pin 11) */ +#define GPIO_CRH_MODE11_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define GPIO_CRH_MODE11_1 ((uint32_t)0x00002000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE12 ((uint32_t)0x00030000) /*!< MODE12[1:0] bits (Port x mode bits, pin 12) */ +#define GPIO_CRH_MODE12_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define GPIO_CRH_MODE12_1 ((uint32_t)0x00020000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE13 ((uint32_t)0x00300000) /*!< MODE13[1:0] bits (Port x mode bits, pin 13) */ +#define GPIO_CRH_MODE13_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define GPIO_CRH_MODE13_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE14 ((uint32_t)0x03000000) /*!< MODE14[1:0] bits (Port x mode bits, pin 14) */ +#define GPIO_CRH_MODE14_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE14_1 ((uint32_t)0x02000000) /*!< Bit 1 */ + +#define GPIO_CRH_MODE15 ((uint32_t)0x30000000) /*!< MODE15[1:0] bits (Port x mode bits, pin 15) */ +#define GPIO_CRH_MODE15_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define GPIO_CRH_MODE15_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF ((uint32_t)0xCCCCCCCC) /*!< Port x configuration bits */ + +#define GPIO_CRH_CNF8 ((uint32_t)0x0000000C) /*!< CNF8[1:0] bits (Port x configuration bits, pin 8) */ +#define GPIO_CRH_CNF8_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define GPIO_CRH_CNF8_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define GPIO_CRH_CNF9 ((uint32_t)0x000000C0) /*!< CNF9[1:0] bits (Port x configuration bits, pin 9) */ +#define GPIO_CRH_CNF9_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define GPIO_CRH_CNF9_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define GPIO_CRH_CNF10 ((uint32_t)0x00000C00) /*!< CNF10[1:0] bits (Port x configuration bits, pin 10) */ +#define GPIO_CRH_CNF10_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define GPIO_CRH_CNF10_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +#define GPIO_CRH_CNF11 ((uint32_t)0x0000C000) /*!< CNF11[1:0] bits (Port x configuration bits, pin 11) */ +#define GPIO_CRH_CNF11_0 ((uint32_t)0x00004000) /*!< Bit 0 */ +#define GPIO_CRH_CNF11_1 ((uint32_t)0x00008000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF12 ((uint32_t)0x000C0000) /*!< CNF12[1:0] bits (Port x configuration bits, pin 12) */ +#define GPIO_CRH_CNF12_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define GPIO_CRH_CNF12_1 ((uint32_t)0x00080000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF13 ((uint32_t)0x00C00000) /*!< CNF13[1:0] bits (Port x configuration bits, pin 13) */ +#define GPIO_CRH_CNF13_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define GPIO_CRH_CNF13_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF14 ((uint32_t)0x0C000000) /*!< CNF14[1:0] bits (Port x configuration bits, pin 14) */ +#define GPIO_CRH_CNF14_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF14_1 ((uint32_t)0x08000000) /*!< Bit 1 */ + +#define GPIO_CRH_CNF15 ((uint32_t)0xC0000000) /*!< CNF15[1:0] bits (Port x configuration bits, pin 15) */ +#define GPIO_CRH_CNF15_0 ((uint32_t)0x40000000) /*!< Bit 0 */ +#define GPIO_CRH_CNF15_1 ((uint32_t)0x80000000) /*!< Bit 1 */ + +/*!<****************** Bit definition for GPIO_IDR register *******************/ +#define GPIO_IDR_IDR0 ((uint16_t)0x0001) /*!< Port input data, bit 0 */ +#define GPIO_IDR_IDR1 ((uint16_t)0x0002) /*!< Port input data, bit 1 */ +#define GPIO_IDR_IDR2 ((uint16_t)0x0004) /*!< Port input data, bit 2 */ +#define GPIO_IDR_IDR3 ((uint16_t)0x0008) /*!< Port input data, bit 3 */ +#define GPIO_IDR_IDR4 ((uint16_t)0x0010) /*!< Port input data, bit 4 */ +#define GPIO_IDR_IDR5 ((uint16_t)0x0020) /*!< Port input data, bit 5 */ +#define GPIO_IDR_IDR6 ((uint16_t)0x0040) /*!< Port input data, bit 6 */ +#define GPIO_IDR_IDR7 ((uint16_t)0x0080) /*!< Port input data, bit 7 */ +#define GPIO_IDR_IDR8 ((uint16_t)0x0100) /*!< Port input data, bit 8 */ +#define GPIO_IDR_IDR9 ((uint16_t)0x0200) /*!< Port input data, bit 9 */ +#define GPIO_IDR_IDR10 ((uint16_t)0x0400) /*!< Port input data, bit 10 */ +#define GPIO_IDR_IDR11 ((uint16_t)0x0800) /*!< Port input data, bit 11 */ +#define GPIO_IDR_IDR12 ((uint16_t)0x1000) /*!< Port input data, bit 12 */ +#define GPIO_IDR_IDR13 ((uint16_t)0x2000) /*!< Port input data, bit 13 */ +#define GPIO_IDR_IDR14 ((uint16_t)0x4000) /*!< Port input data, bit 14 */ +#define GPIO_IDR_IDR15 ((uint16_t)0x8000) /*!< Port input data, bit 15 */ + +/******************* Bit definition for GPIO_ODR register *******************/ +#define GPIO_ODR_ODR0 ((uint16_t)0x0001) /*!< Port output data, bit 0 */ +#define GPIO_ODR_ODR1 ((uint16_t)0x0002) /*!< Port output data, bit 1 */ +#define GPIO_ODR_ODR2 ((uint16_t)0x0004) /*!< Port output data, bit 2 */ +#define GPIO_ODR_ODR3 ((uint16_t)0x0008) /*!< Port output data, bit 3 */ +#define GPIO_ODR_ODR4 ((uint16_t)0x0010) /*!< Port output data, bit 4 */ +#define GPIO_ODR_ODR5 ((uint16_t)0x0020) /*!< Port output data, bit 5 */ +#define GPIO_ODR_ODR6 ((uint16_t)0x0040) /*!< Port output data, bit 6 */ +#define GPIO_ODR_ODR7 ((uint16_t)0x0080) /*!< Port output data, bit 7 */ +#define GPIO_ODR_ODR8 ((uint16_t)0x0100) /*!< Port output data, bit 8 */ +#define GPIO_ODR_ODR9 ((uint16_t)0x0200) /*!< Port output data, bit 9 */ +#define GPIO_ODR_ODR10 ((uint16_t)0x0400) /*!< Port output data, bit 10 */ +#define GPIO_ODR_ODR11 ((uint16_t)0x0800) /*!< Port output data, bit 11 */ +#define GPIO_ODR_ODR12 ((uint16_t)0x1000) /*!< Port output data, bit 12 */ +#define GPIO_ODR_ODR13 ((uint16_t)0x2000) /*!< Port output data, bit 13 */ +#define GPIO_ODR_ODR14 ((uint16_t)0x4000) /*!< Port output data, bit 14 */ +#define GPIO_ODR_ODR15 ((uint16_t)0x8000) /*!< Port output data, bit 15 */ + +/****************** Bit definition for GPIO_BSRR register *******************/ +#define GPIO_BSRR_BS0 ((uint32_t)0x00000001) /*!< Port x Set bit 0 */ +#define GPIO_BSRR_BS1 ((uint32_t)0x00000002) /*!< Port x Set bit 1 */ +#define GPIO_BSRR_BS2 ((uint32_t)0x00000004) /*!< Port x Set bit 2 */ +#define GPIO_BSRR_BS3 ((uint32_t)0x00000008) /*!< Port x Set bit 3 */ +#define GPIO_BSRR_BS4 ((uint32_t)0x00000010) /*!< Port x Set bit 4 */ +#define GPIO_BSRR_BS5 ((uint32_t)0x00000020) /*!< Port x Set bit 5 */ +#define GPIO_BSRR_BS6 ((uint32_t)0x00000040) /*!< Port x Set bit 6 */ +#define GPIO_BSRR_BS7 ((uint32_t)0x00000080) /*!< Port x Set bit 7 */ +#define GPIO_BSRR_BS8 ((uint32_t)0x00000100) /*!< Port x Set bit 8 */ +#define GPIO_BSRR_BS9 ((uint32_t)0x00000200) /*!< Port x Set bit 9 */ +#define GPIO_BSRR_BS10 ((uint32_t)0x00000400) /*!< Port x Set bit 10 */ +#define GPIO_BSRR_BS11 ((uint32_t)0x00000800) /*!< Port x Set bit 11 */ +#define GPIO_BSRR_BS12 ((uint32_t)0x00001000) /*!< Port x Set bit 12 */ +#define GPIO_BSRR_BS13 ((uint32_t)0x00002000) /*!< Port x Set bit 13 */ +#define GPIO_BSRR_BS14 ((uint32_t)0x00004000) /*!< Port x Set bit 14 */ +#define GPIO_BSRR_BS15 ((uint32_t)0x00008000) /*!< Port x Set bit 15 */ + +#define GPIO_BSRR_BR0 ((uint32_t)0x00010000) /*!< Port x Reset bit 0 */ +#define GPIO_BSRR_BR1 ((uint32_t)0x00020000) /*!< Port x Reset bit 1 */ +#define GPIO_BSRR_BR2 ((uint32_t)0x00040000) /*!< Port x Reset bit 2 */ +#define GPIO_BSRR_BR3 ((uint32_t)0x00080000) /*!< Port x Reset bit 3 */ +#define GPIO_BSRR_BR4 ((uint32_t)0x00100000) /*!< Port x Reset bit 4 */ +#define GPIO_BSRR_BR5 ((uint32_t)0x00200000) /*!< Port x Reset bit 5 */ +#define GPIO_BSRR_BR6 ((uint32_t)0x00400000) /*!< Port x Reset bit 6 */ +#define GPIO_BSRR_BR7 ((uint32_t)0x00800000) /*!< Port x Reset bit 7 */ +#define GPIO_BSRR_BR8 ((uint32_t)0x01000000) /*!< Port x Reset bit 8 */ +#define GPIO_BSRR_BR9 ((uint32_t)0x02000000) /*!< Port x Reset bit 9 */ +#define GPIO_BSRR_BR10 ((uint32_t)0x04000000) /*!< Port x Reset bit 10 */ +#define GPIO_BSRR_BR11 ((uint32_t)0x08000000) /*!< Port x Reset bit 11 */ +#define GPIO_BSRR_BR12 ((uint32_t)0x10000000) /*!< Port x Reset bit 12 */ +#define GPIO_BSRR_BR13 ((uint32_t)0x20000000) /*!< Port x Reset bit 13 */ +#define GPIO_BSRR_BR14 ((uint32_t)0x40000000) /*!< Port x Reset bit 14 */ +#define GPIO_BSRR_BR15 ((uint32_t)0x80000000) /*!< Port x Reset bit 15 */ + +/******************* Bit definition for GPIO_BRR register *******************/ +#define GPIO_BRR_BR0 ((uint16_t)0x0001) /*!< Port x Reset bit 0 */ +#define GPIO_BRR_BR1 ((uint16_t)0x0002) /*!< Port x Reset bit 1 */ +#define GPIO_BRR_BR2 ((uint16_t)0x0004) /*!< Port x Reset bit 2 */ +#define GPIO_BRR_BR3 ((uint16_t)0x0008) /*!< Port x Reset bit 3 */ +#define GPIO_BRR_BR4 ((uint16_t)0x0010) /*!< Port x Reset bit 4 */ +#define GPIO_BRR_BR5 ((uint16_t)0x0020) /*!< Port x Reset bit 5 */ +#define GPIO_BRR_BR6 ((uint16_t)0x0040) /*!< Port x Reset bit 6 */ +#define GPIO_BRR_BR7 ((uint16_t)0x0080) /*!< Port x Reset bit 7 */ +#define GPIO_BRR_BR8 ((uint16_t)0x0100) /*!< Port x Reset bit 8 */ +#define GPIO_BRR_BR9 ((uint16_t)0x0200) /*!< Port x Reset bit 9 */ +#define GPIO_BRR_BR10 ((uint16_t)0x0400) /*!< Port x Reset bit 10 */ +#define GPIO_BRR_BR11 ((uint16_t)0x0800) /*!< Port x Reset bit 11 */ +#define GPIO_BRR_BR12 ((uint16_t)0x1000) /*!< Port x Reset bit 12 */ +#define GPIO_BRR_BR13 ((uint16_t)0x2000) /*!< Port x Reset bit 13 */ +#define GPIO_BRR_BR14 ((uint16_t)0x4000) /*!< Port x Reset bit 14 */ +#define GPIO_BRR_BR15 ((uint16_t)0x8000) /*!< Port x Reset bit 15 */ + +/****************** Bit definition for GPIO_LCKR register *******************/ +#define GPIO_LCKR_LCK0 ((uint32_t)0x00000001) /*!< Port x Lock bit 0 */ +#define GPIO_LCKR_LCK1 ((uint32_t)0x00000002) /*!< Port x Lock bit 1 */ +#define GPIO_LCKR_LCK2 ((uint32_t)0x00000004) /*!< Port x Lock bit 2 */ +#define GPIO_LCKR_LCK3 ((uint32_t)0x00000008) /*!< Port x Lock bit 3 */ +#define GPIO_LCKR_LCK4 ((uint32_t)0x00000010) /*!< Port x Lock bit 4 */ +#define GPIO_LCKR_LCK5 ((uint32_t)0x00000020) /*!< Port x Lock bit 5 */ +#define GPIO_LCKR_LCK6 ((uint32_t)0x00000040) /*!< Port x Lock bit 6 */ +#define GPIO_LCKR_LCK7 ((uint32_t)0x00000080) /*!< Port x Lock bit 7 */ +#define GPIO_LCKR_LCK8 ((uint32_t)0x00000100) /*!< Port x Lock bit 8 */ +#define GPIO_LCKR_LCK9 ((uint32_t)0x00000200) /*!< Port x Lock bit 9 */ +#define GPIO_LCKR_LCK10 ((uint32_t)0x00000400) /*!< Port x Lock bit 10 */ +#define GPIO_LCKR_LCK11 ((uint32_t)0x00000800) /*!< Port x Lock bit 11 */ +#define GPIO_LCKR_LCK12 ((uint32_t)0x00001000) /*!< Port x Lock bit 12 */ +#define GPIO_LCKR_LCK13 ((uint32_t)0x00002000) /*!< Port x Lock bit 13 */ +#define GPIO_LCKR_LCK14 ((uint32_t)0x00004000) /*!< Port x Lock bit 14 */ +#define GPIO_LCKR_LCK15 ((uint32_t)0x00008000) /*!< Port x Lock bit 15 */ +#define GPIO_LCKR_LCKK ((uint32_t)0x00010000) /*!< Lock key */ + +/*----------------------------------------------------------------------------*/ + +/****************** Bit definition for AFIO_EVCR register *******************/ +#define AFIO_EVCR_PIN ((uint8_t)0x0F) /*!< PIN[3:0] bits (Pin selection) */ +#define AFIO_EVCR_PIN_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define AFIO_EVCR_PIN_1 ((uint8_t)0x02) /*!< Bit 1 */ +#define AFIO_EVCR_PIN_2 ((uint8_t)0x04) /*!< Bit 2 */ +#define AFIO_EVCR_PIN_3 ((uint8_t)0x08) /*!< Bit 3 */ + +/*!< PIN configuration */ +#define AFIO_EVCR_PIN_PX0 ((uint8_t)0x00) /*!< Pin 0 selected */ +#define AFIO_EVCR_PIN_PX1 ((uint8_t)0x01) /*!< Pin 1 selected */ +#define AFIO_EVCR_PIN_PX2 ((uint8_t)0x02) /*!< Pin 2 selected */ +#define AFIO_EVCR_PIN_PX3 ((uint8_t)0x03) /*!< Pin 3 selected */ +#define AFIO_EVCR_PIN_PX4 ((uint8_t)0x04) /*!< Pin 4 selected */ +#define AFIO_EVCR_PIN_PX5 ((uint8_t)0x05) /*!< Pin 5 selected */ +#define AFIO_EVCR_PIN_PX6 ((uint8_t)0x06) /*!< Pin 6 selected */ +#define AFIO_EVCR_PIN_PX7 ((uint8_t)0x07) /*!< Pin 7 selected */ +#define AFIO_EVCR_PIN_PX8 ((uint8_t)0x08) /*!< Pin 8 selected */ +#define AFIO_EVCR_PIN_PX9 ((uint8_t)0x09) /*!< Pin 9 selected */ +#define AFIO_EVCR_PIN_PX10 ((uint8_t)0x0A) /*!< Pin 10 selected */ +#define AFIO_EVCR_PIN_PX11 ((uint8_t)0x0B) /*!< Pin 11 selected */ +#define AFIO_EVCR_PIN_PX12 ((uint8_t)0x0C) /*!< Pin 12 selected */ +#define AFIO_EVCR_PIN_PX13 ((uint8_t)0x0D) /*!< Pin 13 selected */ +#define AFIO_EVCR_PIN_PX14 ((uint8_t)0x0E) /*!< Pin 14 selected */ +#define AFIO_EVCR_PIN_PX15 ((uint8_t)0x0F) /*!< Pin 15 selected */ + +#define AFIO_EVCR_PORT ((uint8_t)0x70) /*!< PORT[2:0] bits (Port selection) */ +#define AFIO_EVCR_PORT_0 ((uint8_t)0x10) /*!< Bit 0 */ +#define AFIO_EVCR_PORT_1 ((uint8_t)0x20) /*!< Bit 1 */ +#define AFIO_EVCR_PORT_2 ((uint8_t)0x40) /*!< Bit 2 */ + +/*!< PORT configuration */ +#define AFIO_EVCR_PORT_PA ((uint8_t)0x00) /*!< Port A selected */ +#define AFIO_EVCR_PORT_PB ((uint8_t)0x10) /*!< Port B selected */ +#define AFIO_EVCR_PORT_PC ((uint8_t)0x20) /*!< Port C selected */ +#define AFIO_EVCR_PORT_PD ((uint8_t)0x30) /*!< Port D selected */ +#define AFIO_EVCR_PORT_PE ((uint8_t)0x40) /*!< Port E selected */ + +#define AFIO_EVCR_EVOE ((uint8_t)0x80) /*!< Event Output Enable */ + +/****************** Bit definition for AFIO_MAPR register *******************/ +#define AFIO_MAPR_SPI1_REMAP ((uint32_t)0x00000001) /*!< SPI1 remapping */ +#define AFIO_MAPR_I2C1_REMAP ((uint32_t)0x00000002) /*!< I2C1 remapping */ +#define AFIO_MAPR_USART1_REMAP ((uint32_t)0x00000004) /*!< USART1 remapping */ +#define AFIO_MAPR_USART2_REMAP ((uint32_t)0x00000008) /*!< USART2 remapping */ + +#define AFIO_MAPR_USART3_REMAP ((uint32_t)0x00000030) /*!< USART3_REMAP[1:0] bits (USART3 remapping) */ +#define AFIO_MAPR_USART3_REMAP_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define AFIO_MAPR_USART3_REMAP_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +/* USART3_REMAP configuration */ +#define AFIO_MAPR_USART3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (TX/PB10, RX/PB11, CK/PB12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_PARTIALREMAP ((uint32_t)0x00000010) /*!< Partial remap (TX/PC10, RX/PC11, CK/PC12, CTS/PB13, RTS/PB14) */ +#define AFIO_MAPR_USART3_REMAP_FULLREMAP ((uint32_t)0x00000030) /*!< Full remap (TX/PD8, RX/PD9, CK/PD10, CTS/PD11, RTS/PD12) */ + +#define AFIO_MAPR_TIM1_REMAP ((uint32_t)0x000000C0) /*!< TIM1_REMAP[1:0] bits (TIM1 remapping) */ +#define AFIO_MAPR_TIM1_REMAP_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define AFIO_MAPR_TIM1_REMAP_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +/*!< TIM1_REMAP configuration */ +#define AFIO_MAPR_TIM1_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PB12, CH1N/PB13, CH2N/PB14, CH3N/PB15) */ +#define AFIO_MAPR_TIM1_REMAP_PARTIALREMAP ((uint32_t)0x00000040) /*!< Partial remap (ETR/PA12, CH1/PA8, CH2/PA9, CH3/PA10, CH4/PA11, BKIN/PA6, CH1N/PA7, CH2N/PB0, CH3N/PB1) */ +#define AFIO_MAPR_TIM1_REMAP_FULLREMAP ((uint32_t)0x000000C0) /*!< Full remap (ETR/PE7, CH1/PE9, CH2/PE11, CH3/PE13, CH4/PE14, BKIN/PE15, CH1N/PE8, CH2N/PE10, CH3N/PE12) */ + +#define AFIO_MAPR_TIM2_REMAP ((uint32_t)0x00000300) /*!< TIM2_REMAP[1:0] bits (TIM2 remapping) */ +#define AFIO_MAPR_TIM2_REMAP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define AFIO_MAPR_TIM2_REMAP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ + +/*!< TIM2_REMAP configuration */ +#define AFIO_MAPR_TIM2_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/ETR/PA0, CH2/PA1, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP1 ((uint32_t)0x00000100) /*!< Partial remap (CH1/ETR/PA15, CH2/PB3, CH3/PA2, CH4/PA3) */ +#define AFIO_MAPR_TIM2_REMAP_PARTIALREMAP2 ((uint32_t)0x00000200) /*!< Partial remap (CH1/ETR/PA0, CH2/PA1, CH3/PB10, CH4/PB11) */ +#define AFIO_MAPR_TIM2_REMAP_FULLREMAP ((uint32_t)0x00000300) /*!< Full remap (CH1/ETR/PA15, CH2/PB3, CH3/PB10, CH4/PB11) */ + +#define AFIO_MAPR_TIM3_REMAP ((uint32_t)0x00000C00) /*!< TIM3_REMAP[1:0] bits (TIM3 remapping) */ +#define AFIO_MAPR_TIM3_REMAP_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define AFIO_MAPR_TIM3_REMAP_1 ((uint32_t)0x00000800) /*!< Bit 1 */ + +/*!< TIM3_REMAP configuration */ +#define AFIO_MAPR_TIM3_REMAP_NOREMAP ((uint32_t)0x00000000) /*!< No remap (CH1/PA6, CH2/PA7, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_PARTIALREMAP ((uint32_t)0x00000800) /*!< Partial remap (CH1/PB4, CH2/PB5, CH3/PB0, CH4/PB1) */ +#define AFIO_MAPR_TIM3_REMAP_FULLREMAP ((uint32_t)0x00000C00) /*!< Full remap (CH1/PC6, CH2/PC7, CH3/PC8, CH4/PC9) */ + +#define AFIO_MAPR_TIM4_REMAP ((uint32_t)0x00001000) /*!< TIM4_REMAP bit (TIM4 remapping) */ + +#define AFIO_MAPR_CAN_REMAP ((uint32_t)0x00006000) /*!< CAN_REMAP[1:0] bits (CAN Alternate function remapping) */ +#define AFIO_MAPR_CAN_REMAP_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define AFIO_MAPR_CAN_REMAP_1 ((uint32_t)0x00004000) /*!< Bit 1 */ + +/*!< CAN_REMAP configuration */ +#define AFIO_MAPR_CAN_REMAP_REMAP1 ((uint32_t)0x00000000) /*!< CANRX mapped to PA11, CANTX mapped to PA12 */ +#define AFIO_MAPR_CAN_REMAP_REMAP2 ((uint32_t)0x00004000) /*!< CANRX mapped to PB8, CANTX mapped to PB9 */ +#define AFIO_MAPR_CAN_REMAP_REMAP3 ((uint32_t)0x00006000) /*!< CANRX mapped to PD0, CANTX mapped to PD1 */ + +#define AFIO_MAPR_PD01_REMAP ((uint32_t)0x00008000) /*!< Port D0/Port D1 mapping on OSC_IN/OSC_OUT */ +#define AFIO_MAPR_TIM5CH4_IREMAP ((uint32_t)0x00010000) /*!< TIM5 Channel4 Internal Remap */ +#define AFIO_MAPR_ADC1_ETRGINJ_REMAP ((uint32_t)0x00020000) /*!< ADC 1 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC1_ETRGREG_REMAP ((uint32_t)0x00040000) /*!< ADC 1 External Trigger Regular Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGINJ_REMAP ((uint32_t)0x00080000) /*!< ADC 2 External Trigger Injected Conversion remapping */ +#define AFIO_MAPR_ADC2_ETRGREG_REMAP ((uint32_t)0x00100000) /*!< ADC 2 External Trigger Regular Conversion remapping */ + +/*!< SWJ_CFG configuration */ +#define AFIO_MAPR_SWJ_CFG ((uint32_t)0x07000000) /*!< SWJ_CFG[2:0] bits (Serial Wire JTAG configuration) */ +#define AFIO_MAPR_SWJ_CFG_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define AFIO_MAPR_SWJ_CFG_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define AFIO_MAPR_SWJ_CFG_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + +#define AFIO_MAPR_SWJ_CFG_RESET ((uint32_t)0x00000000) /*!< Full SWJ (JTAG-DP + SW-DP) : Reset State */ +#define AFIO_MAPR_SWJ_CFG_NOJNTRST ((uint32_t)0x01000000) /*!< Full SWJ (JTAG-DP + SW-DP) but without JNTRST */ +#define AFIO_MAPR_SWJ_CFG_JTAGDISABLE ((uint32_t)0x02000000) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define AFIO_MAPR_SWJ_CFG_DISABLE ((uint32_t)0x04000000) /*!< JTAG-DP Disabled and SW-DP Disabled */ + +#ifdef STM32F10X_CL +/*!< ETH_REMAP configuration */ + #define AFIO_MAPR_ETH_REMAP ((uint32_t)0x00200000) /*!< SPI3_REMAP bit (Ethernet MAC I/O remapping) */ + +/*!< CAN2_REMAP configuration */ + #define AFIO_MAPR_CAN2_REMAP ((uint32_t)0x00400000) /*!< CAN2_REMAP bit (CAN2 I/O remapping) */ + +/*!< MII_RMII_SEL configuration */ + #define AFIO_MAPR_MII_RMII_SEL ((uint32_t)0x00800000) /*!< MII_RMII_SEL bit (Ethernet MII or RMII selection) */ + +/*!< SPI3_REMAP configuration */ + #define AFIO_MAPR_SPI3_REMAP ((uint32_t)0x10000000) /*!< SPI3_REMAP bit (SPI3 remapping) */ + +/*!< TIM2ITR1_IREMAP configuration */ + #define AFIO_MAPR_TIM2ITR1_IREMAP ((uint32_t)0x20000000) /*!< TIM2ITR1_IREMAP bit (TIM2 internal trigger 1 remapping) */ + +/*!< PTP_PPS_REMAP configuration */ + #define AFIO_MAPR_PTP_PPS_REMAP ((uint32_t)0x40000000) /*!< PTP_PPS_REMAP bit (Ethernet PTP PPS remapping) */ +#endif + +/***************** Bit definition for AFIO_EXTICR1 register *****************/ +#define AFIO_EXTICR1_EXTI0 ((uint16_t)0x000F) /*!< EXTI 0 configuration */ +#define AFIO_EXTICR1_EXTI1 ((uint16_t)0x00F0) /*!< EXTI 1 configuration */ +#define AFIO_EXTICR1_EXTI2 ((uint16_t)0x0F00) /*!< EXTI 2 configuration */ +#define AFIO_EXTICR1_EXTI3 ((uint16_t)0xF000) /*!< EXTI 3 configuration */ + +/*!< EXTI0 configuration */ +#define AFIO_EXTICR1_EXTI0_PA ((uint16_t)0x0000) /*!< PA[0] pin */ +#define AFIO_EXTICR1_EXTI0_PB ((uint16_t)0x0001) /*!< PB[0] pin */ +#define AFIO_EXTICR1_EXTI0_PC ((uint16_t)0x0002) /*!< PC[0] pin */ +#define AFIO_EXTICR1_EXTI0_PD ((uint16_t)0x0003) /*!< PD[0] pin */ +#define AFIO_EXTICR1_EXTI0_PE ((uint16_t)0x0004) /*!< PE[0] pin */ +#define AFIO_EXTICR1_EXTI0_PF ((uint16_t)0x0005) /*!< PF[0] pin */ +#define AFIO_EXTICR1_EXTI0_PG ((uint16_t)0x0006) /*!< PG[0] pin */ + +/*!< EXTI1 configuration */ +#define AFIO_EXTICR1_EXTI1_PA ((uint16_t)0x0000) /*!< PA[1] pin */ +#define AFIO_EXTICR1_EXTI1_PB ((uint16_t)0x0010) /*!< PB[1] pin */ +#define AFIO_EXTICR1_EXTI1_PC ((uint16_t)0x0020) /*!< PC[1] pin */ +#define AFIO_EXTICR1_EXTI1_PD ((uint16_t)0x0030) /*!< PD[1] pin */ +#define AFIO_EXTICR1_EXTI1_PE ((uint16_t)0x0040) /*!< PE[1] pin */ +#define AFIO_EXTICR1_EXTI1_PF ((uint16_t)0x0050) /*!< PF[1] pin */ +#define AFIO_EXTICR1_EXTI1_PG ((uint16_t)0x0060) /*!< PG[1] pin */ + +/*!< EXTI2 configuration */ +#define AFIO_EXTICR1_EXTI2_PA ((uint16_t)0x0000) /*!< PA[2] pin */ +#define AFIO_EXTICR1_EXTI2_PB ((uint16_t)0x0100) /*!< PB[2] pin */ +#define AFIO_EXTICR1_EXTI2_PC ((uint16_t)0x0200) /*!< PC[2] pin */ +#define AFIO_EXTICR1_EXTI2_PD ((uint16_t)0x0300) /*!< PD[2] pin */ +#define AFIO_EXTICR1_EXTI2_PE ((uint16_t)0x0400) /*!< PE[2] pin */ +#define AFIO_EXTICR1_EXTI2_PF ((uint16_t)0x0500) /*!< PF[2] pin */ +#define AFIO_EXTICR1_EXTI2_PG ((uint16_t)0x0600) /*!< PG[2] pin */ + +/*!< EXTI3 configuration */ +#define AFIO_EXTICR1_EXTI3_PA ((uint16_t)0x0000) /*!< PA[3] pin */ +#define AFIO_EXTICR1_EXTI3_PB ((uint16_t)0x1000) /*!< PB[3] pin */ +#define AFIO_EXTICR1_EXTI3_PC ((uint16_t)0x2000) /*!< PC[3] pin */ +#define AFIO_EXTICR1_EXTI3_PD ((uint16_t)0x3000) /*!< PD[3] pin */ +#define AFIO_EXTICR1_EXTI3_PE ((uint16_t)0x4000) /*!< PE[3] pin */ +#define AFIO_EXTICR1_EXTI3_PF ((uint16_t)0x5000) /*!< PF[3] pin */ +#define AFIO_EXTICR1_EXTI3_PG ((uint16_t)0x6000) /*!< PG[3] pin */ + +/***************** Bit definition for AFIO_EXTICR2 register *****************/ +#define AFIO_EXTICR2_EXTI4 ((uint16_t)0x000F) /*!< EXTI 4 configuration */ +#define AFIO_EXTICR2_EXTI5 ((uint16_t)0x00F0) /*!< EXTI 5 configuration */ +#define AFIO_EXTICR2_EXTI6 ((uint16_t)0x0F00) /*!< EXTI 6 configuration */ +#define AFIO_EXTICR2_EXTI7 ((uint16_t)0xF000) /*!< EXTI 7 configuration */ + +/*!< EXTI4 configuration */ +#define AFIO_EXTICR2_EXTI4_PA ((uint16_t)0x0000) /*!< PA[4] pin */ +#define AFIO_EXTICR2_EXTI4_PB ((uint16_t)0x0001) /*!< PB[4] pin */ +#define AFIO_EXTICR2_EXTI4_PC ((uint16_t)0x0002) /*!< PC[4] pin */ +#define AFIO_EXTICR2_EXTI4_PD ((uint16_t)0x0003) /*!< PD[4] pin */ +#define AFIO_EXTICR2_EXTI4_PE ((uint16_t)0x0004) /*!< PE[4] pin */ +#define AFIO_EXTICR2_EXTI4_PF ((uint16_t)0x0005) /*!< PF[4] pin */ +#define AFIO_EXTICR2_EXTI4_PG ((uint16_t)0x0006) /*!< PG[4] pin */ + +/* EXTI5 configuration */ +#define AFIO_EXTICR2_EXTI5_PA ((uint16_t)0x0000) /*!< PA[5] pin */ +#define AFIO_EXTICR2_EXTI5_PB ((uint16_t)0x0010) /*!< PB[5] pin */ +#define AFIO_EXTICR2_EXTI5_PC ((uint16_t)0x0020) /*!< PC[5] pin */ +#define AFIO_EXTICR2_EXTI5_PD ((uint16_t)0x0030) /*!< PD[5] pin */ +#define AFIO_EXTICR2_EXTI5_PE ((uint16_t)0x0040) /*!< PE[5] pin */ +#define AFIO_EXTICR2_EXTI5_PF ((uint16_t)0x0050) /*!< PF[5] pin */ +#define AFIO_EXTICR2_EXTI5_PG ((uint16_t)0x0060) /*!< PG[5] pin */ + +/*!< EXTI6 configuration */ +#define AFIO_EXTICR2_EXTI6_PA ((uint16_t)0x0000) /*!< PA[6] pin */ +#define AFIO_EXTICR2_EXTI6_PB ((uint16_t)0x0100) /*!< PB[6] pin */ +#define AFIO_EXTICR2_EXTI6_PC ((uint16_t)0x0200) /*!< PC[6] pin */ +#define AFIO_EXTICR2_EXTI6_PD ((uint16_t)0x0300) /*!< PD[6] pin */ +#define AFIO_EXTICR2_EXTI6_PE ((uint16_t)0x0400) /*!< PE[6] pin */ +#define AFIO_EXTICR2_EXTI6_PF ((uint16_t)0x0500) /*!< PF[6] pin */ +#define AFIO_EXTICR2_EXTI6_PG ((uint16_t)0x0600) /*!< PG[6] pin */ + +/*!< EXTI7 configuration */ +#define AFIO_EXTICR2_EXTI7_PA ((uint16_t)0x0000) /*!< PA[7] pin */ +#define AFIO_EXTICR2_EXTI7_PB ((uint16_t)0x1000) /*!< PB[7] pin */ +#define AFIO_EXTICR2_EXTI7_PC ((uint16_t)0x2000) /*!< PC[7] pin */ +#define AFIO_EXTICR2_EXTI7_PD ((uint16_t)0x3000) /*!< PD[7] pin */ +#define AFIO_EXTICR2_EXTI7_PE ((uint16_t)0x4000) /*!< PE[7] pin */ +#define AFIO_EXTICR2_EXTI7_PF ((uint16_t)0x5000) /*!< PF[7] pin */ +#define AFIO_EXTICR2_EXTI7_PG ((uint16_t)0x6000) /*!< PG[7] pin */ + +/***************** Bit definition for AFIO_EXTICR3 register *****************/ +#define AFIO_EXTICR3_EXTI8 ((uint16_t)0x000F) /*!< EXTI 8 configuration */ +#define AFIO_EXTICR3_EXTI9 ((uint16_t)0x00F0) /*!< EXTI 9 configuration */ +#define AFIO_EXTICR3_EXTI10 ((uint16_t)0x0F00) /*!< EXTI 10 configuration */ +#define AFIO_EXTICR3_EXTI11 ((uint16_t)0xF000) /*!< EXTI 11 configuration */ + +/*!< EXTI8 configuration */ +#define AFIO_EXTICR3_EXTI8_PA ((uint16_t)0x0000) /*!< PA[8] pin */ +#define AFIO_EXTICR3_EXTI8_PB ((uint16_t)0x0001) /*!< PB[8] pin */ +#define AFIO_EXTICR3_EXTI8_PC ((uint16_t)0x0002) /*!< PC[8] pin */ +#define AFIO_EXTICR3_EXTI8_PD ((uint16_t)0x0003) /*!< PD[8] pin */ +#define AFIO_EXTICR3_EXTI8_PE ((uint16_t)0x0004) /*!< PE[8] pin */ +#define AFIO_EXTICR3_EXTI8_PF ((uint16_t)0x0005) /*!< PF[8] pin */ +#define AFIO_EXTICR3_EXTI8_PG ((uint16_t)0x0006) /*!< PG[8] pin */ + +/*!< EXTI9 configuration */ +#define AFIO_EXTICR3_EXTI9_PA ((uint16_t)0x0000) /*!< PA[9] pin */ +#define AFIO_EXTICR3_EXTI9_PB ((uint16_t)0x0010) /*!< PB[9] pin */ +#define AFIO_EXTICR3_EXTI9_PC ((uint16_t)0x0020) /*!< PC[9] pin */ +#define AFIO_EXTICR3_EXTI9_PD ((uint16_t)0x0030) /*!< PD[9] pin */ +#define AFIO_EXTICR3_EXTI9_PE ((uint16_t)0x0040) /*!< PE[9] pin */ +#define AFIO_EXTICR3_EXTI9_PF ((uint16_t)0x0050) /*!< PF[9] pin */ +#define AFIO_EXTICR3_EXTI9_PG ((uint16_t)0x0060) /*!< PG[9] pin */ + +/*!< EXTI10 configuration */ +#define AFIO_EXTICR3_EXTI10_PA ((uint16_t)0x0000) /*!< PA[10] pin */ +#define AFIO_EXTICR3_EXTI10_PB ((uint16_t)0x0100) /*!< PB[10] pin */ +#define AFIO_EXTICR3_EXTI10_PC ((uint16_t)0x0200) /*!< PC[10] pin */ +#define AFIO_EXTICR3_EXTI10_PD ((uint16_t)0x0300) /*!< PD[10] pin */ +#define AFIO_EXTICR3_EXTI10_PE ((uint16_t)0x0400) /*!< PE[10] pin */ +#define AFIO_EXTICR3_EXTI10_PF ((uint16_t)0x0500) /*!< PF[10] pin */ +#define AFIO_EXTICR3_EXTI10_PG ((uint16_t)0x0600) /*!< PG[10] pin */ + +/*!< EXTI11 configuration */ +#define AFIO_EXTICR3_EXTI11_PA ((uint16_t)0x0000) /*!< PA[11] pin */ +#define AFIO_EXTICR3_EXTI11_PB ((uint16_t)0x1000) /*!< PB[11] pin */ +#define AFIO_EXTICR3_EXTI11_PC ((uint16_t)0x2000) /*!< PC[11] pin */ +#define AFIO_EXTICR3_EXTI11_PD ((uint16_t)0x3000) /*!< PD[11] pin */ +#define AFIO_EXTICR3_EXTI11_PE ((uint16_t)0x4000) /*!< PE[11] pin */ +#define AFIO_EXTICR3_EXTI11_PF ((uint16_t)0x5000) /*!< PF[11] pin */ +#define AFIO_EXTICR3_EXTI11_PG ((uint16_t)0x6000) /*!< PG[11] pin */ + +/***************** Bit definition for AFIO_EXTICR4 register *****************/ +#define AFIO_EXTICR4_EXTI12 ((uint16_t)0x000F) /*!< EXTI 12 configuration */ +#define AFIO_EXTICR4_EXTI13 ((uint16_t)0x00F0) /*!< EXTI 13 configuration */ +#define AFIO_EXTICR4_EXTI14 ((uint16_t)0x0F00) /*!< EXTI 14 configuration */ +#define AFIO_EXTICR4_EXTI15 ((uint16_t)0xF000) /*!< EXTI 15 configuration */ + +/* EXTI12 configuration */ +#define AFIO_EXTICR4_EXTI12_PA ((uint16_t)0x0000) /*!< PA[12] pin */ +#define AFIO_EXTICR4_EXTI12_PB ((uint16_t)0x0001) /*!< PB[12] pin */ +#define AFIO_EXTICR4_EXTI12_PC ((uint16_t)0x0002) /*!< PC[12] pin */ +#define AFIO_EXTICR4_EXTI12_PD ((uint16_t)0x0003) /*!< PD[12] pin */ +#define AFIO_EXTICR4_EXTI12_PE ((uint16_t)0x0004) /*!< PE[12] pin */ +#define AFIO_EXTICR4_EXTI12_PF ((uint16_t)0x0005) /*!< PF[12] pin */ +#define AFIO_EXTICR4_EXTI12_PG ((uint16_t)0x0006) /*!< PG[12] pin */ + +/* EXTI13 configuration */ +#define AFIO_EXTICR4_EXTI13_PA ((uint16_t)0x0000) /*!< PA[13] pin */ +#define AFIO_EXTICR4_EXTI13_PB ((uint16_t)0x0010) /*!< PB[13] pin */ +#define AFIO_EXTICR4_EXTI13_PC ((uint16_t)0x0020) /*!< PC[13] pin */ +#define AFIO_EXTICR4_EXTI13_PD ((uint16_t)0x0030) /*!< PD[13] pin */ +#define AFIO_EXTICR4_EXTI13_PE ((uint16_t)0x0040) /*!< PE[13] pin */ +#define AFIO_EXTICR4_EXTI13_PF ((uint16_t)0x0050) /*!< PF[13] pin */ +#define AFIO_EXTICR4_EXTI13_PG ((uint16_t)0x0060) /*!< PG[13] pin */ + +/*!< EXTI14 configuration */ +#define AFIO_EXTICR4_EXTI14_PA ((uint16_t)0x0000) /*!< PA[14] pin */ +#define AFIO_EXTICR4_EXTI14_PB ((uint16_t)0x0100) /*!< PB[14] pin */ +#define AFIO_EXTICR4_EXTI14_PC ((uint16_t)0x0200) /*!< PC[14] pin */ +#define AFIO_EXTICR4_EXTI14_PD ((uint16_t)0x0300) /*!< PD[14] pin */ +#define AFIO_EXTICR4_EXTI14_PE ((uint16_t)0x0400) /*!< PE[14] pin */ +#define AFIO_EXTICR4_EXTI14_PF ((uint16_t)0x0500) /*!< PF[14] pin */ +#define AFIO_EXTICR4_EXTI14_PG ((uint16_t)0x0600) /*!< PG[14] pin */ + +/*!< EXTI15 configuration */ +#define AFIO_EXTICR4_EXTI15_PA ((uint16_t)0x0000) /*!< PA[15] pin */ +#define AFIO_EXTICR4_EXTI15_PB ((uint16_t)0x1000) /*!< PB[15] pin */ +#define AFIO_EXTICR4_EXTI15_PC ((uint16_t)0x2000) /*!< PC[15] pin */ +#define AFIO_EXTICR4_EXTI15_PD ((uint16_t)0x3000) /*!< PD[15] pin */ +#define AFIO_EXTICR4_EXTI15_PE ((uint16_t)0x4000) /*!< PE[15] pin */ +#define AFIO_EXTICR4_EXTI15_PF ((uint16_t)0x5000) /*!< PF[15] pin */ +#define AFIO_EXTICR4_EXTI15_PG ((uint16_t)0x6000) /*!< PG[15] pin */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM15_REMAP ((uint32_t)0x00000001) /*!< TIM15 remapping */ +#define AFIO_MAPR2_TIM16_REMAP ((uint32_t)0x00000002) /*!< TIM16 remapping */ +#define AFIO_MAPR2_TIM17_REMAP ((uint32_t)0x00000004) /*!< TIM17 remapping */ +#define AFIO_MAPR2_CEC_REMAP ((uint32_t)0x00000008) /*!< CEC remapping */ +#define AFIO_MAPR2_TIM1_DMA_REMAP ((uint32_t)0x00000010) /*!< TIM1_DMA remapping */ +#endif + +#ifdef STM32F10X_HD_VL +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#define AFIO_MAPR2_TIM67_DAC_DMA_REMAP ((uint32_t)0x00000800) /*!< TIM6/TIM7 and DAC DMA remapping */ +#define AFIO_MAPR2_TIM12_REMAP ((uint32_t)0x00001000) /*!< TIM12 remapping */ +#define AFIO_MAPR2_MISC_REMAP ((uint32_t)0x00002000) /*!< Miscellaneous remapping */ +#endif + +#ifdef STM32F10X_XL +/****************** Bit definition for AFIO_MAPR2 register ******************/ +#define AFIO_MAPR2_TIM9_REMAP ((uint32_t)0x00000020) /*!< TIM9 remapping */ +#define AFIO_MAPR2_TIM10_REMAP ((uint32_t)0x00000040) /*!< TIM10 remapping */ +#define AFIO_MAPR2_TIM11_REMAP ((uint32_t)0x00000080) /*!< TIM11 remapping */ +#define AFIO_MAPR2_TIM13_REMAP ((uint32_t)0x00000100) /*!< TIM13 remapping */ +#define AFIO_MAPR2_TIM14_REMAP ((uint32_t)0x00000200) /*!< TIM14 remapping */ +#define AFIO_MAPR2_FSMC_NADV_REMAP ((uint32_t)0x00000400) /*!< FSMC NADV remapping */ +#endif + +/******************************************************************************/ +/* */ +/* SystemTick */ +/* */ +/******************************************************************************/ + +/***************** Bit definition for SysTick_CTRL register *****************/ +#define SysTick_CTRL_ENABLE ((uint32_t)0x00000001) /*!< Counter enable */ +#define SysTick_CTRL_TICKINT ((uint32_t)0x00000002) /*!< Counting down to 0 pends the SysTick handler */ +#define SysTick_CTRL_CLKSOURCE ((uint32_t)0x00000004) /*!< Clock source */ +#define SysTick_CTRL_COUNTFLAG ((uint32_t)0x00010000) /*!< Count Flag */ + +/***************** Bit definition for SysTick_LOAD register *****************/ +#define SysTick_LOAD_RELOAD ((uint32_t)0x00FFFFFF) /*!< Value to load into the SysTick Current Value Register when the counter reaches 0 */ + +/***************** Bit definition for SysTick_VAL register ******************/ +#define SysTick_VAL_CURRENT ((uint32_t)0x00FFFFFF) /*!< Current value at the time the register is accessed */ + +/***************** Bit definition for SysTick_CALIB register ****************/ +#define SysTick_CALIB_TENMS ((uint32_t)0x00FFFFFF) /*!< Reload value to use for 10ms timing */ +#define SysTick_CALIB_SKEW ((uint32_t)0x40000000) /*!< Calibration value is not exactly 10 ms */ +#define SysTick_CALIB_NOREF ((uint32_t)0x80000000) /*!< The reference clock is not provided */ + +/******************************************************************************/ +/* */ +/* Nested Vectored Interrupt Controller */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for NVIC_ISER register *******************/ +#define NVIC_ISER_SETENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt set enable bits */ +#define NVIC_ISER_SETENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISER_SETENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISER_SETENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISER_SETENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISER_SETENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISER_SETENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISER_SETENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISER_SETENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISER_SETENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISER_SETENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISER_SETENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISER_SETENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISER_SETENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISER_SETENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISER_SETENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISER_SETENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISER_SETENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISER_SETENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISER_SETENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISER_SETENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISER_SETENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISER_SETENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISER_SETENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISER_SETENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISER_SETENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISER_SETENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISER_SETENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISER_SETENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISER_SETENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISER_SETENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISER_SETENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISER_SETENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICER register *******************/ +#define NVIC_ICER_CLRENA ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-enable bits */ +#define NVIC_ICER_CLRENA_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICER_CLRENA_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICER_CLRENA_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICER_CLRENA_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICER_CLRENA_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICER_CLRENA_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICER_CLRENA_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICER_CLRENA_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICER_CLRENA_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICER_CLRENA_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICER_CLRENA_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICER_CLRENA_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICER_CLRENA_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICER_CLRENA_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICER_CLRENA_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICER_CLRENA_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICER_CLRENA_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICER_CLRENA_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICER_CLRENA_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICER_CLRENA_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICER_CLRENA_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICER_CLRENA_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICER_CLRENA_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICER_CLRENA_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICER_CLRENA_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICER_CLRENA_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICER_CLRENA_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICER_CLRENA_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICER_CLRENA_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICER_CLRENA_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICER_CLRENA_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICER_CLRENA_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ISPR register *******************/ +#define NVIC_ISPR_SETPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt set-pending bits */ +#define NVIC_ISPR_SETPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ISPR_SETPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ISPR_SETPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ISPR_SETPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ISPR_SETPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ISPR_SETPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ISPR_SETPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ISPR_SETPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ISPR_SETPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ISPR_SETPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ISPR_SETPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ISPR_SETPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ISPR_SETPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ISPR_SETPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ISPR_SETPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ISPR_SETPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ISPR_SETPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ISPR_SETPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ISPR_SETPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ISPR_SETPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ISPR_SETPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ISPR_SETPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ISPR_SETPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ISPR_SETPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ISPR_SETPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ISPR_SETPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ISPR_SETPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ISPR_SETPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ISPR_SETPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ISPR_SETPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ISPR_SETPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ISPR_SETPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_ICPR register *******************/ +#define NVIC_ICPR_CLRPEND ((uint32_t)0xFFFFFFFF) /*!< Interrupt clear-pending bits */ +#define NVIC_ICPR_CLRPEND_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_ICPR_CLRPEND_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_ICPR_CLRPEND_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_ICPR_CLRPEND_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_ICPR_CLRPEND_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_ICPR_CLRPEND_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_ICPR_CLRPEND_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_ICPR_CLRPEND_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_ICPR_CLRPEND_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_ICPR_CLRPEND_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_ICPR_CLRPEND_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_ICPR_CLRPEND_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_ICPR_CLRPEND_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_ICPR_CLRPEND_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_ICPR_CLRPEND_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_ICPR_CLRPEND_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_ICPR_CLRPEND_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_ICPR_CLRPEND_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_ICPR_CLRPEND_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_ICPR_CLRPEND_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_ICPR_CLRPEND_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_ICPR_CLRPEND_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_ICPR_CLRPEND_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_ICPR_CLRPEND_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_ICPR_CLRPEND_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_ICPR_CLRPEND_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_ICPR_CLRPEND_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_ICPR_CLRPEND_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_ICPR_CLRPEND_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_ICPR_CLRPEND_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_ICPR_CLRPEND_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_ICPR_CLRPEND_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_IABR register *******************/ +#define NVIC_IABR_ACTIVE ((uint32_t)0xFFFFFFFF) /*!< Interrupt active flags */ +#define NVIC_IABR_ACTIVE_0 ((uint32_t)0x00000001) /*!< bit 0 */ +#define NVIC_IABR_ACTIVE_1 ((uint32_t)0x00000002) /*!< bit 1 */ +#define NVIC_IABR_ACTIVE_2 ((uint32_t)0x00000004) /*!< bit 2 */ +#define NVIC_IABR_ACTIVE_3 ((uint32_t)0x00000008) /*!< bit 3 */ +#define NVIC_IABR_ACTIVE_4 ((uint32_t)0x00000010) /*!< bit 4 */ +#define NVIC_IABR_ACTIVE_5 ((uint32_t)0x00000020) /*!< bit 5 */ +#define NVIC_IABR_ACTIVE_6 ((uint32_t)0x00000040) /*!< bit 6 */ +#define NVIC_IABR_ACTIVE_7 ((uint32_t)0x00000080) /*!< bit 7 */ +#define NVIC_IABR_ACTIVE_8 ((uint32_t)0x00000100) /*!< bit 8 */ +#define NVIC_IABR_ACTIVE_9 ((uint32_t)0x00000200) /*!< bit 9 */ +#define NVIC_IABR_ACTIVE_10 ((uint32_t)0x00000400) /*!< bit 10 */ +#define NVIC_IABR_ACTIVE_11 ((uint32_t)0x00000800) /*!< bit 11 */ +#define NVIC_IABR_ACTIVE_12 ((uint32_t)0x00001000) /*!< bit 12 */ +#define NVIC_IABR_ACTIVE_13 ((uint32_t)0x00002000) /*!< bit 13 */ +#define NVIC_IABR_ACTIVE_14 ((uint32_t)0x00004000) /*!< bit 14 */ +#define NVIC_IABR_ACTIVE_15 ((uint32_t)0x00008000) /*!< bit 15 */ +#define NVIC_IABR_ACTIVE_16 ((uint32_t)0x00010000) /*!< bit 16 */ +#define NVIC_IABR_ACTIVE_17 ((uint32_t)0x00020000) /*!< bit 17 */ +#define NVIC_IABR_ACTIVE_18 ((uint32_t)0x00040000) /*!< bit 18 */ +#define NVIC_IABR_ACTIVE_19 ((uint32_t)0x00080000) /*!< bit 19 */ +#define NVIC_IABR_ACTIVE_20 ((uint32_t)0x00100000) /*!< bit 20 */ +#define NVIC_IABR_ACTIVE_21 ((uint32_t)0x00200000) /*!< bit 21 */ +#define NVIC_IABR_ACTIVE_22 ((uint32_t)0x00400000) /*!< bit 22 */ +#define NVIC_IABR_ACTIVE_23 ((uint32_t)0x00800000) /*!< bit 23 */ +#define NVIC_IABR_ACTIVE_24 ((uint32_t)0x01000000) /*!< bit 24 */ +#define NVIC_IABR_ACTIVE_25 ((uint32_t)0x02000000) /*!< bit 25 */ +#define NVIC_IABR_ACTIVE_26 ((uint32_t)0x04000000) /*!< bit 26 */ +#define NVIC_IABR_ACTIVE_27 ((uint32_t)0x08000000) /*!< bit 27 */ +#define NVIC_IABR_ACTIVE_28 ((uint32_t)0x10000000) /*!< bit 28 */ +#define NVIC_IABR_ACTIVE_29 ((uint32_t)0x20000000) /*!< bit 29 */ +#define NVIC_IABR_ACTIVE_30 ((uint32_t)0x40000000) /*!< bit 30 */ +#define NVIC_IABR_ACTIVE_31 ((uint32_t)0x80000000) /*!< bit 31 */ + +/****************** Bit definition for NVIC_PRI0 register *******************/ +#define NVIC_IPR0_PRI_0 ((uint32_t)0x000000FF) /*!< Priority of interrupt 0 */ +#define NVIC_IPR0_PRI_1 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 1 */ +#define NVIC_IPR0_PRI_2 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 2 */ +#define NVIC_IPR0_PRI_3 ((uint32_t)0xFF000000) /*!< Priority of interrupt 3 */ + +/****************** Bit definition for NVIC_PRI1 register *******************/ +#define NVIC_IPR1_PRI_4 ((uint32_t)0x000000FF) /*!< Priority of interrupt 4 */ +#define NVIC_IPR1_PRI_5 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 5 */ +#define NVIC_IPR1_PRI_6 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 6 */ +#define NVIC_IPR1_PRI_7 ((uint32_t)0xFF000000) /*!< Priority of interrupt 7 */ + +/****************** Bit definition for NVIC_PRI2 register *******************/ +#define NVIC_IPR2_PRI_8 ((uint32_t)0x000000FF) /*!< Priority of interrupt 8 */ +#define NVIC_IPR2_PRI_9 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 9 */ +#define NVIC_IPR2_PRI_10 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 10 */ +#define NVIC_IPR2_PRI_11 ((uint32_t)0xFF000000) /*!< Priority of interrupt 11 */ + +/****************** Bit definition for NVIC_PRI3 register *******************/ +#define NVIC_IPR3_PRI_12 ((uint32_t)0x000000FF) /*!< Priority of interrupt 12 */ +#define NVIC_IPR3_PRI_13 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 13 */ +#define NVIC_IPR3_PRI_14 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 14 */ +#define NVIC_IPR3_PRI_15 ((uint32_t)0xFF000000) /*!< Priority of interrupt 15 */ + +/****************** Bit definition for NVIC_PRI4 register *******************/ +#define NVIC_IPR4_PRI_16 ((uint32_t)0x000000FF) /*!< Priority of interrupt 16 */ +#define NVIC_IPR4_PRI_17 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 17 */ +#define NVIC_IPR4_PRI_18 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 18 */ +#define NVIC_IPR4_PRI_19 ((uint32_t)0xFF000000) /*!< Priority of interrupt 19 */ + +/****************** Bit definition for NVIC_PRI5 register *******************/ +#define NVIC_IPR5_PRI_20 ((uint32_t)0x000000FF) /*!< Priority of interrupt 20 */ +#define NVIC_IPR5_PRI_21 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 21 */ +#define NVIC_IPR5_PRI_22 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 22 */ +#define NVIC_IPR5_PRI_23 ((uint32_t)0xFF000000) /*!< Priority of interrupt 23 */ + +/****************** Bit definition for NVIC_PRI6 register *******************/ +#define NVIC_IPR6_PRI_24 ((uint32_t)0x000000FF) /*!< Priority of interrupt 24 */ +#define NVIC_IPR6_PRI_25 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 25 */ +#define NVIC_IPR6_PRI_26 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 26 */ +#define NVIC_IPR6_PRI_27 ((uint32_t)0xFF000000) /*!< Priority of interrupt 27 */ + +/****************** Bit definition for NVIC_PRI7 register *******************/ +#define NVIC_IPR7_PRI_28 ((uint32_t)0x000000FF) /*!< Priority of interrupt 28 */ +#define NVIC_IPR7_PRI_29 ((uint32_t)0x0000FF00) /*!< Priority of interrupt 29 */ +#define NVIC_IPR7_PRI_30 ((uint32_t)0x00FF0000) /*!< Priority of interrupt 30 */ +#define NVIC_IPR7_PRI_31 ((uint32_t)0xFF000000) /*!< Priority of interrupt 31 */ + +/****************** Bit definition for SCB_CPUID register *******************/ +#define SCB_CPUID_REVISION ((uint32_t)0x0000000F) /*!< Implementation defined revision number */ +#define SCB_CPUID_PARTNO ((uint32_t)0x0000FFF0) /*!< Number of processor within family */ +#define SCB_CPUID_Constant ((uint32_t)0x000F0000) /*!< Reads as 0x0F */ +#define SCB_CPUID_VARIANT ((uint32_t)0x00F00000) /*!< Implementation defined variant number */ +#define SCB_CPUID_IMPLEMENTER ((uint32_t)0xFF000000) /*!< Implementer code. ARM is 0x41 */ + +/******************* Bit definition for SCB_ICSR register *******************/ +#define SCB_ICSR_VECTACTIVE ((uint32_t)0x000001FF) /*!< Active ISR number field */ +#define SCB_ICSR_RETTOBASE ((uint32_t)0x00000800) /*!< All active exceptions minus the IPSR_current_exception yields the empty set */ +#define SCB_ICSR_VECTPENDING ((uint32_t)0x003FF000) /*!< Pending ISR number field */ +#define SCB_ICSR_ISRPENDING ((uint32_t)0x00400000) /*!< Interrupt pending flag */ +#define SCB_ICSR_ISRPREEMPT ((uint32_t)0x00800000) /*!< It indicates that a pending interrupt becomes active in the next running cycle */ +#define SCB_ICSR_PENDSTCLR ((uint32_t)0x02000000) /*!< Clear pending SysTick bit */ +#define SCB_ICSR_PENDSTSET ((uint32_t)0x04000000) /*!< Set pending SysTick bit */ +#define SCB_ICSR_PENDSVCLR ((uint32_t)0x08000000) /*!< Clear pending pendSV bit */ +#define SCB_ICSR_PENDSVSET ((uint32_t)0x10000000) /*!< Set pending pendSV bit */ +#define SCB_ICSR_NMIPENDSET ((uint32_t)0x80000000) /*!< Set pending NMI bit */ + +/******************* Bit definition for SCB_VTOR register *******************/ +#define SCB_VTOR_TBLOFF ((uint32_t)0x1FFFFF80) /*!< Vector table base offset field */ +#define SCB_VTOR_TBLBASE ((uint32_t)0x20000000) /*!< Table base in code(0) or RAM(1) */ + +/*!<***************** Bit definition for SCB_AIRCR register *******************/ +#define SCB_AIRCR_VECTRESET ((uint32_t)0x00000001) /*!< System Reset bit */ +#define SCB_AIRCR_VECTCLRACTIVE ((uint32_t)0x00000002) /*!< Clear active vector bit */ +#define SCB_AIRCR_SYSRESETREQ ((uint32_t)0x00000004) /*!< Requests chip control logic to generate a reset */ + +#define SCB_AIRCR_PRIGROUP ((uint32_t)0x00000700) /*!< PRIGROUP[2:0] bits (Priority group) */ +#define SCB_AIRCR_PRIGROUP_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define SCB_AIRCR_PRIGROUP_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define SCB_AIRCR_PRIGROUP_2 ((uint32_t)0x00000400) /*!< Bit 2 */ + +/* prority group configuration */ +#define SCB_AIRCR_PRIGROUP0 ((uint32_t)0x00000000) /*!< Priority group=0 (7 bits of pre-emption priority, 1 bit of subpriority) */ +#define SCB_AIRCR_PRIGROUP1 ((uint32_t)0x00000100) /*!< Priority group=1 (6 bits of pre-emption priority, 2 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP2 ((uint32_t)0x00000200) /*!< Priority group=2 (5 bits of pre-emption priority, 3 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP3 ((uint32_t)0x00000300) /*!< Priority group=3 (4 bits of pre-emption priority, 4 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP4 ((uint32_t)0x00000400) /*!< Priority group=4 (3 bits of pre-emption priority, 5 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP5 ((uint32_t)0x00000500) /*!< Priority group=5 (2 bits of pre-emption priority, 6 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP6 ((uint32_t)0x00000600) /*!< Priority group=6 (1 bit of pre-emption priority, 7 bits of subpriority) */ +#define SCB_AIRCR_PRIGROUP7 ((uint32_t)0x00000700) /*!< Priority group=7 (no pre-emption priority, 8 bits of subpriority) */ + +#define SCB_AIRCR_ENDIANESS ((uint32_t)0x00008000) /*!< Data endianness bit */ +#define SCB_AIRCR_VECTKEY ((uint32_t)0xFFFF0000) /*!< Register key (VECTKEY) - Reads as 0xFA05 (VECTKEYSTAT) */ + +/******************* Bit definition for SCB_SCR register ********************/ +#define SCB_SCR_SLEEPONEXIT ((uint8_t)0x02) /*!< Sleep on exit bit */ +#define SCB_SCR_SLEEPDEEP ((uint8_t)0x04) /*!< Sleep deep bit */ +#define SCB_SCR_SEVONPEND ((uint8_t)0x10) /*!< Wake up from WFE */ + +/******************** Bit definition for SCB_CCR register *******************/ +#define SCB_CCR_NONBASETHRDENA ((uint16_t)0x0001) /*!< Thread mode can be entered from any level in Handler mode by controlled return value */ +#define SCB_CCR_USERSETMPEND ((uint16_t)0x0002) /*!< Enables user code to write the Software Trigger Interrupt register to trigger (pend) a Main exception */ +#define SCB_CCR_UNALIGN_TRP ((uint16_t)0x0008) /*!< Trap for unaligned access */ +#define SCB_CCR_DIV_0_TRP ((uint16_t)0x0010) /*!< Trap on Divide by 0 */ +#define SCB_CCR_BFHFNMIGN ((uint16_t)0x0100) /*!< Handlers running at priority -1 and -2 */ +#define SCB_CCR_STKALIGN ((uint16_t)0x0200) /*!< On exception entry, the SP used prior to the exception is adjusted to be 8-byte aligned */ + +/******************* Bit definition for SCB_SHPR register ********************/ +#define SCB_SHPR_PRI_N ((uint32_t)0x000000FF) /*!< Priority of system handler 4,8, and 12. Mem Manage, reserved and Debug Monitor */ +#define SCB_SHPR_PRI_N1 ((uint32_t)0x0000FF00) /*!< Priority of system handler 5,9, and 13. Bus Fault, reserved and reserved */ +#define SCB_SHPR_PRI_N2 ((uint32_t)0x00FF0000) /*!< Priority of system handler 6,10, and 14. Usage Fault, reserved and PendSV */ +#define SCB_SHPR_PRI_N3 ((uint32_t)0xFF000000) /*!< Priority of system handler 7,11, and 15. Reserved, SVCall and SysTick */ + +/****************** Bit definition for SCB_SHCSR register *******************/ +#define SCB_SHCSR_MEMFAULTACT ((uint32_t)0x00000001) /*!< MemManage is active */ +#define SCB_SHCSR_BUSFAULTACT ((uint32_t)0x00000002) /*!< BusFault is active */ +#define SCB_SHCSR_USGFAULTACT ((uint32_t)0x00000008) /*!< UsageFault is active */ +#define SCB_SHCSR_SVCALLACT ((uint32_t)0x00000080) /*!< SVCall is active */ +#define SCB_SHCSR_MONITORACT ((uint32_t)0x00000100) /*!< Monitor is active */ +#define SCB_SHCSR_PENDSVACT ((uint32_t)0x00000400) /*!< PendSV is active */ +#define SCB_SHCSR_SYSTICKACT ((uint32_t)0x00000800) /*!< SysTick is active */ +#define SCB_SHCSR_USGFAULTPENDED ((uint32_t)0x00001000) /*!< Usage Fault is pended */ +#define SCB_SHCSR_MEMFAULTPENDED ((uint32_t)0x00002000) /*!< MemManage is pended */ +#define SCB_SHCSR_BUSFAULTPENDED ((uint32_t)0x00004000) /*!< Bus Fault is pended */ +#define SCB_SHCSR_SVCALLPENDED ((uint32_t)0x00008000) /*!< SVCall is pended */ +#define SCB_SHCSR_MEMFAULTENA ((uint32_t)0x00010000) /*!< MemManage enable */ +#define SCB_SHCSR_BUSFAULTENA ((uint32_t)0x00020000) /*!< Bus Fault enable */ +#define SCB_SHCSR_USGFAULTENA ((uint32_t)0x00040000) /*!< UsageFault enable */ + +/******************* Bit definition for SCB_CFSR register *******************/ +/*!< MFSR */ +#define SCB_CFSR_IACCVIOL ((uint32_t)0x00000001) /*!< Instruction access violation */ +#define SCB_CFSR_DACCVIOL ((uint32_t)0x00000002) /*!< Data access violation */ +#define SCB_CFSR_MUNSTKERR ((uint32_t)0x00000008) /*!< Unstacking error */ +#define SCB_CFSR_MSTKERR ((uint32_t)0x00000010) /*!< Stacking error */ +#define SCB_CFSR_MMARVALID ((uint32_t)0x00000080) /*!< Memory Manage Address Register address valid flag */ +/*!< BFSR */ +#define SCB_CFSR_IBUSERR ((uint32_t)0x00000100) /*!< Instruction bus error flag */ +#define SCB_CFSR_PRECISERR ((uint32_t)0x00000200) /*!< Precise data bus error */ +#define SCB_CFSR_IMPRECISERR ((uint32_t)0x00000400) /*!< Imprecise data bus error */ +#define SCB_CFSR_UNSTKERR ((uint32_t)0x00000800) /*!< Unstacking error */ +#define SCB_CFSR_STKERR ((uint32_t)0x00001000) /*!< Stacking error */ +#define SCB_CFSR_BFARVALID ((uint32_t)0x00008000) /*!< Bus Fault Address Register address valid flag */ +/*!< UFSR */ +#define SCB_CFSR_UNDEFINSTR ((uint32_t)0x00010000) /*!< The processor attempt to execute an undefined instruction */ +#define SCB_CFSR_INVSTATE ((uint32_t)0x00020000) /*!< Invalid combination of EPSR and instruction */ +#define SCB_CFSR_INVPC ((uint32_t)0x00040000) /*!< Attempt to load EXC_RETURN into pc illegally */ +#define SCB_CFSR_NOCP ((uint32_t)0x00080000) /*!< Attempt to use a coprocessor instruction */ +#define SCB_CFSR_UNALIGNED ((uint32_t)0x01000000) /*!< Fault occurs when there is an attempt to make an unaligned memory access */ +#define SCB_CFSR_DIVBYZERO ((uint32_t)0x02000000) /*!< Fault occurs when SDIV or DIV instruction is used with a divisor of 0 */ + +/******************* Bit definition for SCB_HFSR register *******************/ +#define SCB_HFSR_VECTTBL ((uint32_t)0x00000002) /*!< Fault occurs because of vector table read on exception processing */ +#define SCB_HFSR_FORCED ((uint32_t)0x40000000) /*!< Hard Fault activated when a configurable Fault was received and cannot activate */ +#define SCB_HFSR_DEBUGEVT ((uint32_t)0x80000000) /*!< Fault related to debug */ + +/******************* Bit definition for SCB_DFSR register *******************/ +#define SCB_DFSR_HALTED ((uint8_t)0x01) /*!< Halt request flag */ +#define SCB_DFSR_BKPT ((uint8_t)0x02) /*!< BKPT flag */ +#define SCB_DFSR_DWTTRAP ((uint8_t)0x04) /*!< Data Watchpoint and Trace (DWT) flag */ +#define SCB_DFSR_VCATCH ((uint8_t)0x08) /*!< Vector catch flag */ +#define SCB_DFSR_EXTERNAL ((uint8_t)0x10) /*!< External debug request flag */ + +/******************* Bit definition for SCB_MMFAR register ******************/ +#define SCB_MMFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Mem Manage fault address field */ + +/******************* Bit definition for SCB_BFAR register *******************/ +#define SCB_BFAR_ADDRESS ((uint32_t)0xFFFFFFFF) /*!< Bus fault address field */ + +/******************* Bit definition for SCB_afsr register *******************/ +#define SCB_AFSR_IMPDEF ((uint32_t)0xFFFFFFFF) /*!< Implementation defined */ + +/******************************************************************************/ +/* */ +/* External Interrupt/Event Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for EXTI_IMR register *******************/ +#define EXTI_IMR_MR0 ((uint32_t)0x00000001) /*!< Interrupt Mask on line 0 */ +#define EXTI_IMR_MR1 ((uint32_t)0x00000002) /*!< Interrupt Mask on line 1 */ +#define EXTI_IMR_MR2 ((uint32_t)0x00000004) /*!< Interrupt Mask on line 2 */ +#define EXTI_IMR_MR3 ((uint32_t)0x00000008) /*!< Interrupt Mask on line 3 */ +#define EXTI_IMR_MR4 ((uint32_t)0x00000010) /*!< Interrupt Mask on line 4 */ +#define EXTI_IMR_MR5 ((uint32_t)0x00000020) /*!< Interrupt Mask on line 5 */ +#define EXTI_IMR_MR6 ((uint32_t)0x00000040) /*!< Interrupt Mask on line 6 */ +#define EXTI_IMR_MR7 ((uint32_t)0x00000080) /*!< Interrupt Mask on line 7 */ +#define EXTI_IMR_MR8 ((uint32_t)0x00000100) /*!< Interrupt Mask on line 8 */ +#define EXTI_IMR_MR9 ((uint32_t)0x00000200) /*!< Interrupt Mask on line 9 */ +#define EXTI_IMR_MR10 ((uint32_t)0x00000400) /*!< Interrupt Mask on line 10 */ +#define EXTI_IMR_MR11 ((uint32_t)0x00000800) /*!< Interrupt Mask on line 11 */ +#define EXTI_IMR_MR12 ((uint32_t)0x00001000) /*!< Interrupt Mask on line 12 */ +#define EXTI_IMR_MR13 ((uint32_t)0x00002000) /*!< Interrupt Mask on line 13 */ +#define EXTI_IMR_MR14 ((uint32_t)0x00004000) /*!< Interrupt Mask on line 14 */ +#define EXTI_IMR_MR15 ((uint32_t)0x00008000) /*!< Interrupt Mask on line 15 */ +#define EXTI_IMR_MR16 ((uint32_t)0x00010000) /*!< Interrupt Mask on line 16 */ +#define EXTI_IMR_MR17 ((uint32_t)0x00020000) /*!< Interrupt Mask on line 17 */ +#define EXTI_IMR_MR18 ((uint32_t)0x00040000) /*!< Interrupt Mask on line 18 */ +#define EXTI_IMR_MR19 ((uint32_t)0x00080000) /*!< Interrupt Mask on line 19 */ + +/******************* Bit definition for EXTI_EMR register *******************/ +#define EXTI_EMR_MR0 ((uint32_t)0x00000001) /*!< Event Mask on line 0 */ +#define EXTI_EMR_MR1 ((uint32_t)0x00000002) /*!< Event Mask on line 1 */ +#define EXTI_EMR_MR2 ((uint32_t)0x00000004) /*!< Event Mask on line 2 */ +#define EXTI_EMR_MR3 ((uint32_t)0x00000008) /*!< Event Mask on line 3 */ +#define EXTI_EMR_MR4 ((uint32_t)0x00000010) /*!< Event Mask on line 4 */ +#define EXTI_EMR_MR5 ((uint32_t)0x00000020) /*!< Event Mask on line 5 */ +#define EXTI_EMR_MR6 ((uint32_t)0x00000040) /*!< Event Mask on line 6 */ +#define EXTI_EMR_MR7 ((uint32_t)0x00000080) /*!< Event Mask on line 7 */ +#define EXTI_EMR_MR8 ((uint32_t)0x00000100) /*!< Event Mask on line 8 */ +#define EXTI_EMR_MR9 ((uint32_t)0x00000200) /*!< Event Mask on line 9 */ +#define EXTI_EMR_MR10 ((uint32_t)0x00000400) /*!< Event Mask on line 10 */ +#define EXTI_EMR_MR11 ((uint32_t)0x00000800) /*!< Event Mask on line 11 */ +#define EXTI_EMR_MR12 ((uint32_t)0x00001000) /*!< Event Mask on line 12 */ +#define EXTI_EMR_MR13 ((uint32_t)0x00002000) /*!< Event Mask on line 13 */ +#define EXTI_EMR_MR14 ((uint32_t)0x00004000) /*!< Event Mask on line 14 */ +#define EXTI_EMR_MR15 ((uint32_t)0x00008000) /*!< Event Mask on line 15 */ +#define EXTI_EMR_MR16 ((uint32_t)0x00010000) /*!< Event Mask on line 16 */ +#define EXTI_EMR_MR17 ((uint32_t)0x00020000) /*!< Event Mask on line 17 */ +#define EXTI_EMR_MR18 ((uint32_t)0x00040000) /*!< Event Mask on line 18 */ +#define EXTI_EMR_MR19 ((uint32_t)0x00080000) /*!< Event Mask on line 19 */ + +/****************** Bit definition for EXTI_RTSR register *******************/ +#define EXTI_RTSR_TR0 ((uint32_t)0x00000001) /*!< Rising trigger event configuration bit of line 0 */ +#define EXTI_RTSR_TR1 ((uint32_t)0x00000002) /*!< Rising trigger event configuration bit of line 1 */ +#define EXTI_RTSR_TR2 ((uint32_t)0x00000004) /*!< Rising trigger event configuration bit of line 2 */ +#define EXTI_RTSR_TR3 ((uint32_t)0x00000008) /*!< Rising trigger event configuration bit of line 3 */ +#define EXTI_RTSR_TR4 ((uint32_t)0x00000010) /*!< Rising trigger event configuration bit of line 4 */ +#define EXTI_RTSR_TR5 ((uint32_t)0x00000020) /*!< Rising trigger event configuration bit of line 5 */ +#define EXTI_RTSR_TR6 ((uint32_t)0x00000040) /*!< Rising trigger event configuration bit of line 6 */ +#define EXTI_RTSR_TR7 ((uint32_t)0x00000080) /*!< Rising trigger event configuration bit of line 7 */ +#define EXTI_RTSR_TR8 ((uint32_t)0x00000100) /*!< Rising trigger event configuration bit of line 8 */ +#define EXTI_RTSR_TR9 ((uint32_t)0x00000200) /*!< Rising trigger event configuration bit of line 9 */ +#define EXTI_RTSR_TR10 ((uint32_t)0x00000400) /*!< Rising trigger event configuration bit of line 10 */ +#define EXTI_RTSR_TR11 ((uint32_t)0x00000800) /*!< Rising trigger event configuration bit of line 11 */ +#define EXTI_RTSR_TR12 ((uint32_t)0x00001000) /*!< Rising trigger event configuration bit of line 12 */ +#define EXTI_RTSR_TR13 ((uint32_t)0x00002000) /*!< Rising trigger event configuration bit of line 13 */ +#define EXTI_RTSR_TR14 ((uint32_t)0x00004000) /*!< Rising trigger event configuration bit of line 14 */ +#define EXTI_RTSR_TR15 ((uint32_t)0x00008000) /*!< Rising trigger event configuration bit of line 15 */ +#define EXTI_RTSR_TR16 ((uint32_t)0x00010000) /*!< Rising trigger event configuration bit of line 16 */ +#define EXTI_RTSR_TR17 ((uint32_t)0x00020000) /*!< Rising trigger event configuration bit of line 17 */ +#define EXTI_RTSR_TR18 ((uint32_t)0x00040000) /*!< Rising trigger event configuration bit of line 18 */ +#define EXTI_RTSR_TR19 ((uint32_t)0x00080000) /*!< Rising trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_FTSR register *******************/ +#define EXTI_FTSR_TR0 ((uint32_t)0x00000001) /*!< Falling trigger event configuration bit of line 0 */ +#define EXTI_FTSR_TR1 ((uint32_t)0x00000002) /*!< Falling trigger event configuration bit of line 1 */ +#define EXTI_FTSR_TR2 ((uint32_t)0x00000004) /*!< Falling trigger event configuration bit of line 2 */ +#define EXTI_FTSR_TR3 ((uint32_t)0x00000008) /*!< Falling trigger event configuration bit of line 3 */ +#define EXTI_FTSR_TR4 ((uint32_t)0x00000010) /*!< Falling trigger event configuration bit of line 4 */ +#define EXTI_FTSR_TR5 ((uint32_t)0x00000020) /*!< Falling trigger event configuration bit of line 5 */ +#define EXTI_FTSR_TR6 ((uint32_t)0x00000040) /*!< Falling trigger event configuration bit of line 6 */ +#define EXTI_FTSR_TR7 ((uint32_t)0x00000080) /*!< Falling trigger event configuration bit of line 7 */ +#define EXTI_FTSR_TR8 ((uint32_t)0x00000100) /*!< Falling trigger event configuration bit of line 8 */ +#define EXTI_FTSR_TR9 ((uint32_t)0x00000200) /*!< Falling trigger event configuration bit of line 9 */ +#define EXTI_FTSR_TR10 ((uint32_t)0x00000400) /*!< Falling trigger event configuration bit of line 10 */ +#define EXTI_FTSR_TR11 ((uint32_t)0x00000800) /*!< Falling trigger event configuration bit of line 11 */ +#define EXTI_FTSR_TR12 ((uint32_t)0x00001000) /*!< Falling trigger event configuration bit of line 12 */ +#define EXTI_FTSR_TR13 ((uint32_t)0x00002000) /*!< Falling trigger event configuration bit of line 13 */ +#define EXTI_FTSR_TR14 ((uint32_t)0x00004000) /*!< Falling trigger event configuration bit of line 14 */ +#define EXTI_FTSR_TR15 ((uint32_t)0x00008000) /*!< Falling trigger event configuration bit of line 15 */ +#define EXTI_FTSR_TR16 ((uint32_t)0x00010000) /*!< Falling trigger event configuration bit of line 16 */ +#define EXTI_FTSR_TR17 ((uint32_t)0x00020000) /*!< Falling trigger event configuration bit of line 17 */ +#define EXTI_FTSR_TR18 ((uint32_t)0x00040000) /*!< Falling trigger event configuration bit of line 18 */ +#define EXTI_FTSR_TR19 ((uint32_t)0x00080000) /*!< Falling trigger event configuration bit of line 19 */ + +/****************** Bit definition for EXTI_SWIER register ******************/ +#define EXTI_SWIER_SWIER0 ((uint32_t)0x00000001) /*!< Software Interrupt on line 0 */ +#define EXTI_SWIER_SWIER1 ((uint32_t)0x00000002) /*!< Software Interrupt on line 1 */ +#define EXTI_SWIER_SWIER2 ((uint32_t)0x00000004) /*!< Software Interrupt on line 2 */ +#define EXTI_SWIER_SWIER3 ((uint32_t)0x00000008) /*!< Software Interrupt on line 3 */ +#define EXTI_SWIER_SWIER4 ((uint32_t)0x00000010) /*!< Software Interrupt on line 4 */ +#define EXTI_SWIER_SWIER5 ((uint32_t)0x00000020) /*!< Software Interrupt on line 5 */ +#define EXTI_SWIER_SWIER6 ((uint32_t)0x00000040) /*!< Software Interrupt on line 6 */ +#define EXTI_SWIER_SWIER7 ((uint32_t)0x00000080) /*!< Software Interrupt on line 7 */ +#define EXTI_SWIER_SWIER8 ((uint32_t)0x00000100) /*!< Software Interrupt on line 8 */ +#define EXTI_SWIER_SWIER9 ((uint32_t)0x00000200) /*!< Software Interrupt on line 9 */ +#define EXTI_SWIER_SWIER10 ((uint32_t)0x00000400) /*!< Software Interrupt on line 10 */ +#define EXTI_SWIER_SWIER11 ((uint32_t)0x00000800) /*!< Software Interrupt on line 11 */ +#define EXTI_SWIER_SWIER12 ((uint32_t)0x00001000) /*!< Software Interrupt on line 12 */ +#define EXTI_SWIER_SWIER13 ((uint32_t)0x00002000) /*!< Software Interrupt on line 13 */ +#define EXTI_SWIER_SWIER14 ((uint32_t)0x00004000) /*!< Software Interrupt on line 14 */ +#define EXTI_SWIER_SWIER15 ((uint32_t)0x00008000) /*!< Software Interrupt on line 15 */ +#define EXTI_SWIER_SWIER16 ((uint32_t)0x00010000) /*!< Software Interrupt on line 16 */ +#define EXTI_SWIER_SWIER17 ((uint32_t)0x00020000) /*!< Software Interrupt on line 17 */ +#define EXTI_SWIER_SWIER18 ((uint32_t)0x00040000) /*!< Software Interrupt on line 18 */ +#define EXTI_SWIER_SWIER19 ((uint32_t)0x00080000) /*!< Software Interrupt on line 19 */ + +/******************* Bit definition for EXTI_PR register ********************/ +#define EXTI_PR_PR0 ((uint32_t)0x00000001) /*!< Pending bit for line 0 */ +#define EXTI_PR_PR1 ((uint32_t)0x00000002) /*!< Pending bit for line 1 */ +#define EXTI_PR_PR2 ((uint32_t)0x00000004) /*!< Pending bit for line 2 */ +#define EXTI_PR_PR3 ((uint32_t)0x00000008) /*!< Pending bit for line 3 */ +#define EXTI_PR_PR4 ((uint32_t)0x00000010) /*!< Pending bit for line 4 */ +#define EXTI_PR_PR5 ((uint32_t)0x00000020) /*!< Pending bit for line 5 */ +#define EXTI_PR_PR6 ((uint32_t)0x00000040) /*!< Pending bit for line 6 */ +#define EXTI_PR_PR7 ((uint32_t)0x00000080) /*!< Pending bit for line 7 */ +#define EXTI_PR_PR8 ((uint32_t)0x00000100) /*!< Pending bit for line 8 */ +#define EXTI_PR_PR9 ((uint32_t)0x00000200) /*!< Pending bit for line 9 */ +#define EXTI_PR_PR10 ((uint32_t)0x00000400) /*!< Pending bit for line 10 */ +#define EXTI_PR_PR11 ((uint32_t)0x00000800) /*!< Pending bit for line 11 */ +#define EXTI_PR_PR12 ((uint32_t)0x00001000) /*!< Pending bit for line 12 */ +#define EXTI_PR_PR13 ((uint32_t)0x00002000) /*!< Pending bit for line 13 */ +#define EXTI_PR_PR14 ((uint32_t)0x00004000) /*!< Pending bit for line 14 */ +#define EXTI_PR_PR15 ((uint32_t)0x00008000) /*!< Pending bit for line 15 */ +#define EXTI_PR_PR16 ((uint32_t)0x00010000) /*!< Pending bit for line 16 */ +#define EXTI_PR_PR17 ((uint32_t)0x00020000) /*!< Pending bit for line 17 */ +#define EXTI_PR_PR18 ((uint32_t)0x00040000) /*!< Pending bit for line 18 */ +#define EXTI_PR_PR19 ((uint32_t)0x00080000) /*!< Pending bit for line 19 */ + +/******************************************************************************/ +/* */ +/* DMA Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for DMA_ISR register ********************/ +#define DMA_ISR_GIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt flag */ +#define DMA_ISR_TCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete flag */ +#define DMA_ISR_HTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer flag */ +#define DMA_ISR_TEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error flag */ +#define DMA_ISR_GIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt flag */ +#define DMA_ISR_TCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete flag */ +#define DMA_ISR_HTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer flag */ +#define DMA_ISR_TEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error flag */ +#define DMA_ISR_GIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt flag */ +#define DMA_ISR_TCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete flag */ +#define DMA_ISR_HTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer flag */ +#define DMA_ISR_TEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error flag */ +#define DMA_ISR_GIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt flag */ +#define DMA_ISR_TCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete flag */ +#define DMA_ISR_HTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer flag */ +#define DMA_ISR_TEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error flag */ +#define DMA_ISR_GIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt flag */ +#define DMA_ISR_TCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete flag */ +#define DMA_ISR_HTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer flag */ +#define DMA_ISR_TEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error flag */ +#define DMA_ISR_GIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt flag */ +#define DMA_ISR_TCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete flag */ +#define DMA_ISR_HTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer flag */ +#define DMA_ISR_TEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error flag */ +#define DMA_ISR_GIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt flag */ +#define DMA_ISR_TCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete flag */ +#define DMA_ISR_HTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer flag */ +#define DMA_ISR_TEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error flag */ + +/******************* Bit definition for DMA_IFCR register *******************/ +#define DMA_IFCR_CGIF1 ((uint32_t)0x00000001) /*!< Channel 1 Global interrupt clear */ +#define DMA_IFCR_CTCIF1 ((uint32_t)0x00000002) /*!< Channel 1 Transfer Complete clear */ +#define DMA_IFCR_CHTIF1 ((uint32_t)0x00000004) /*!< Channel 1 Half Transfer clear */ +#define DMA_IFCR_CTEIF1 ((uint32_t)0x00000008) /*!< Channel 1 Transfer Error clear */ +#define DMA_IFCR_CGIF2 ((uint32_t)0x00000010) /*!< Channel 2 Global interrupt clear */ +#define DMA_IFCR_CTCIF2 ((uint32_t)0x00000020) /*!< Channel 2 Transfer Complete clear */ +#define DMA_IFCR_CHTIF2 ((uint32_t)0x00000040) /*!< Channel 2 Half Transfer clear */ +#define DMA_IFCR_CTEIF2 ((uint32_t)0x00000080) /*!< Channel 2 Transfer Error clear */ +#define DMA_IFCR_CGIF3 ((uint32_t)0x00000100) /*!< Channel 3 Global interrupt clear */ +#define DMA_IFCR_CTCIF3 ((uint32_t)0x00000200) /*!< Channel 3 Transfer Complete clear */ +#define DMA_IFCR_CHTIF3 ((uint32_t)0x00000400) /*!< Channel 3 Half Transfer clear */ +#define DMA_IFCR_CTEIF3 ((uint32_t)0x00000800) /*!< Channel 3 Transfer Error clear */ +#define DMA_IFCR_CGIF4 ((uint32_t)0x00001000) /*!< Channel 4 Global interrupt clear */ +#define DMA_IFCR_CTCIF4 ((uint32_t)0x00002000) /*!< Channel 4 Transfer Complete clear */ +#define DMA_IFCR_CHTIF4 ((uint32_t)0x00004000) /*!< Channel 4 Half Transfer clear */ +#define DMA_IFCR_CTEIF4 ((uint32_t)0x00008000) /*!< Channel 4 Transfer Error clear */ +#define DMA_IFCR_CGIF5 ((uint32_t)0x00010000) /*!< Channel 5 Global interrupt clear */ +#define DMA_IFCR_CTCIF5 ((uint32_t)0x00020000) /*!< Channel 5 Transfer Complete clear */ +#define DMA_IFCR_CHTIF5 ((uint32_t)0x00040000) /*!< Channel 5 Half Transfer clear */ +#define DMA_IFCR_CTEIF5 ((uint32_t)0x00080000) /*!< Channel 5 Transfer Error clear */ +#define DMA_IFCR_CGIF6 ((uint32_t)0x00100000) /*!< Channel 6 Global interrupt clear */ +#define DMA_IFCR_CTCIF6 ((uint32_t)0x00200000) /*!< Channel 6 Transfer Complete clear */ +#define DMA_IFCR_CHTIF6 ((uint32_t)0x00400000) /*!< Channel 6 Half Transfer clear */ +#define DMA_IFCR_CTEIF6 ((uint32_t)0x00800000) /*!< Channel 6 Transfer Error clear */ +#define DMA_IFCR_CGIF7 ((uint32_t)0x01000000) /*!< Channel 7 Global interrupt clear */ +#define DMA_IFCR_CTCIF7 ((uint32_t)0x02000000) /*!< Channel 7 Transfer Complete clear */ +#define DMA_IFCR_CHTIF7 ((uint32_t)0x04000000) /*!< Channel 7 Half Transfer clear */ +#define DMA_IFCR_CTEIF7 ((uint32_t)0x08000000) /*!< Channel 7 Transfer Error clear */ + +/******************* Bit definition for DMA_CCR1 register *******************/ +#define DMA_CCR1_EN ((uint16_t)0x0001) /*!< Channel enable*/ +#define DMA_CCR1_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR1_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR1_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR1_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR1_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR1_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR1_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR1_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR1_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR1_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR1_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR1_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR1_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR1_PL ((uint16_t)0x3000) /*!< PL[1:0] bits(Channel Priority level) */ +#define DMA_CCR1_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR1_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR1_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR2 register *******************/ +#define DMA_CCR2_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR2_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR2_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR2_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR2_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR2_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR2_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR2_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR2_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR2_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR2_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR2_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR2_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR2_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR2_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR2_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR2_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR2_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR3 register *******************/ +#define DMA_CCR3_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR3_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR3_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR3_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR3_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR3_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR3_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR3_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR3_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR3_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR3_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR3_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR3_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR3_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR3_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR3_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR3_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR3_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/*!<****************** Bit definition for DMA_CCR4 register *******************/ +#define DMA_CCR4_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR4_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR4_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR4_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR4_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR4_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR4_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR4_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR4_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR4_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR4_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR4_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR4_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR4_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR4_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR4_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR4_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR4_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/****************** Bit definition for DMA_CCR5 register *******************/ +#define DMA_CCR5_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR5_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR5_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR5_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR5_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR5_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR5_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR5_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR5_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR5_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR5_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR5_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR5_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR5_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR5_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR5_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR5_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR5_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode enable */ + +/******************* Bit definition for DMA_CCR6 register *******************/ +#define DMA_CCR6_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR6_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR6_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR6_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR6_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR6_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR6_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR6_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR6_PSIZE ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR6_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR6_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR6_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR6_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR6_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR6_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR6_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR6_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR6_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode */ + +/******************* Bit definition for DMA_CCR7 register *******************/ +#define DMA_CCR7_EN ((uint16_t)0x0001) /*!< Channel enable */ +#define DMA_CCR7_TCIE ((uint16_t)0x0002) /*!< Transfer complete interrupt enable */ +#define DMA_CCR7_HTIE ((uint16_t)0x0004) /*!< Half Transfer interrupt enable */ +#define DMA_CCR7_TEIE ((uint16_t)0x0008) /*!< Transfer error interrupt enable */ +#define DMA_CCR7_DIR ((uint16_t)0x0010) /*!< Data transfer direction */ +#define DMA_CCR7_CIRC ((uint16_t)0x0020) /*!< Circular mode */ +#define DMA_CCR7_PINC ((uint16_t)0x0040) /*!< Peripheral increment mode */ +#define DMA_CCR7_MINC ((uint16_t)0x0080) /*!< Memory increment mode */ + +#define DMA_CCR7_PSIZE , ((uint16_t)0x0300) /*!< PSIZE[1:0] bits (Peripheral size) */ +#define DMA_CCR7_PSIZE_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define DMA_CCR7_PSIZE_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define DMA_CCR7_MSIZE ((uint16_t)0x0C00) /*!< MSIZE[1:0] bits (Memory size) */ +#define DMA_CCR7_MSIZE_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define DMA_CCR7_MSIZE_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define DMA_CCR7_PL ((uint16_t)0x3000) /*!< PL[1:0] bits (Channel Priority level) */ +#define DMA_CCR7_PL_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define DMA_CCR7_PL_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define DMA_CCR7_MEM2MEM ((uint16_t)0x4000) /*!< Memory to memory mode enable */ + +/****************** Bit definition for DMA_CNDTR1 register ******************/ +#define DMA_CNDTR1_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR2 register ******************/ +#define DMA_CNDTR2_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR3 register ******************/ +#define DMA_CNDTR3_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR4 register ******************/ +#define DMA_CNDTR4_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR5 register ******************/ +#define DMA_CNDTR5_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR6 register ******************/ +#define DMA_CNDTR6_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CNDTR7 register ******************/ +#define DMA_CNDTR7_NDT ((uint16_t)0xFFFF) /*!< Number of data to Transfer */ + +/****************** Bit definition for DMA_CPAR1 register *******************/ +#define DMA_CPAR1_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR2 register *******************/ +#define DMA_CPAR2_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR3 register *******************/ +#define DMA_CPAR3_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + + +/****************** Bit definition for DMA_CPAR4 register *******************/ +#define DMA_CPAR4_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR5 register *******************/ +#define DMA_CPAR5_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CPAR6 register *******************/ +#define DMA_CPAR6_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + + +/****************** Bit definition for DMA_CPAR7 register *******************/ +#define DMA_CPAR7_PA ((uint32_t)0xFFFFFFFF) /*!< Peripheral Address */ + +/****************** Bit definition for DMA_CMAR1 register *******************/ +#define DMA_CMAR1_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR2 register *******************/ +#define DMA_CMAR2_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR3 register *******************/ +#define DMA_CMAR3_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + + +/****************** Bit definition for DMA_CMAR4 register *******************/ +#define DMA_CMAR4_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR5 register *******************/ +#define DMA_CMAR5_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR6 register *******************/ +#define DMA_CMAR6_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/****************** Bit definition for DMA_CMAR7 register *******************/ +#define DMA_CMAR7_MA ((uint32_t)0xFFFFFFFF) /*!< Memory Address */ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for ADC_SR register ********************/ +#define ADC_SR_AWD ((uint8_t)0x01) /*!< Analog watchdog flag */ +#define ADC_SR_EOC ((uint8_t)0x02) /*!< End of conversion */ +#define ADC_SR_JEOC ((uint8_t)0x04) /*!< Injected channel end of conversion */ +#define ADC_SR_JSTRT ((uint8_t)0x08) /*!< Injected channel Start flag */ +#define ADC_SR_STRT ((uint8_t)0x10) /*!< Regular channel Start flag */ + +/******************* Bit definition for ADC_CR1 register ********************/ +#define ADC_CR1_AWDCH ((uint32_t)0x0000001F) /*!< AWDCH[4:0] bits (Analog watchdog channel select bits) */ +#define ADC_CR1_AWDCH_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_CR1_AWDCH_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_CR1_AWDCH_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_CR1_AWDCH_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_CR1_AWDCH_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_CR1_EOCIE ((uint32_t)0x00000020) /*!< Interrupt enable for EOC */ +#define ADC_CR1_AWDIE ((uint32_t)0x00000040) /*!< Analog Watchdog interrupt enable */ +#define ADC_CR1_JEOCIE ((uint32_t)0x00000080) /*!< Interrupt enable for injected channels */ +#define ADC_CR1_SCAN ((uint32_t)0x00000100) /*!< Scan mode */ +#define ADC_CR1_AWDSGL ((uint32_t)0x00000200) /*!< Enable the watchdog on a single channel in scan mode */ +#define ADC_CR1_JAUTO ((uint32_t)0x00000400) /*!< Automatic injected group conversion */ +#define ADC_CR1_DISCEN ((uint32_t)0x00000800) /*!< Discontinuous mode on regular channels */ +#define ADC_CR1_JDISCEN ((uint32_t)0x00001000) /*!< Discontinuous mode on injected channels */ + +#define ADC_CR1_DISCNUM ((uint32_t)0x0000E000) /*!< DISCNUM[2:0] bits (Discontinuous mode channel count) */ +#define ADC_CR1_DISCNUM_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define ADC_CR1_DISCNUM_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define ADC_CR1_DISCNUM_2 ((uint32_t)0x00008000) /*!< Bit 2 */ + +#define ADC_CR1_DUALMOD ((uint32_t)0x000F0000) /*!< DUALMOD[3:0] bits (Dual mode selection) */ +#define ADC_CR1_DUALMOD_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define ADC_CR1_DUALMOD_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define ADC_CR1_DUALMOD_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define ADC_CR1_DUALMOD_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define ADC_CR1_JAWDEN ((uint32_t)0x00400000) /*!< Analog watchdog enable on injected channels */ +#define ADC_CR1_AWDEN ((uint32_t)0x00800000) /*!< Analog watchdog enable on regular channels */ + + +/******************* Bit definition for ADC_CR2 register ********************/ +#define ADC_CR2_ADON ((uint32_t)0x00000001) /*!< A/D Converter ON / OFF */ +#define ADC_CR2_CONT ((uint32_t)0x00000002) /*!< Continuous Conversion */ +#define ADC_CR2_CAL ((uint32_t)0x00000004) /*!< A/D Calibration */ +#define ADC_CR2_RSTCAL ((uint32_t)0x00000008) /*!< Reset Calibration */ +#define ADC_CR2_DMA ((uint32_t)0x00000100) /*!< Direct Memory access mode */ +#define ADC_CR2_ALIGN ((uint32_t)0x00000800) /*!< Data Alignment */ + +#define ADC_CR2_JEXTSEL ((uint32_t)0x00007000) /*!< JEXTSEL[2:0] bits (External event select for injected group) */ +#define ADC_CR2_JEXTSEL_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_CR2_JEXTSEL_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_CR2_JEXTSEL_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_CR2_JEXTTRIG ((uint32_t)0x00008000) /*!< External Trigger Conversion mode for injected channels */ + +#define ADC_CR2_EXTSEL ((uint32_t)0x000E0000) /*!< EXTSEL[2:0] bits (External Event Select for regular group) */ +#define ADC_CR2_EXTSEL_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define ADC_CR2_EXTSEL_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define ADC_CR2_EXTSEL_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +#define ADC_CR2_EXTTRIG ((uint32_t)0x00100000) /*!< External Trigger Conversion mode for regular channels */ +#define ADC_CR2_JSWSTART ((uint32_t)0x00200000) /*!< Start Conversion of injected channels */ +#define ADC_CR2_SWSTART ((uint32_t)0x00400000) /*!< Start Conversion of regular channels */ +#define ADC_CR2_TSVREFE ((uint32_t)0x00800000) /*!< Temperature Sensor and VREFINT Enable */ + +/****************** Bit definition for ADC_SMPR1 register *******************/ +#define ADC_SMPR1_SMP10 ((uint32_t)0x00000007) /*!< SMP10[2:0] bits (Channel 10 Sample time selection) */ +#define ADC_SMPR1_SMP10_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SMPR1_SMP10_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SMPR1_SMP10_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP11 ((uint32_t)0x00000038) /*!< SMP11[2:0] bits (Channel 11 Sample time selection) */ +#define ADC_SMPR1_SMP11_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define ADC_SMPR1_SMP11_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define ADC_SMPR1_SMP11_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP12 ((uint32_t)0x000001C0) /*!< SMP12[2:0] bits (Channel 12 Sample time selection) */ +#define ADC_SMPR1_SMP12_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define ADC_SMPR1_SMP12_1 ((uint32_t)0x00000080) /*!< Bit 1 */ +#define ADC_SMPR1_SMP12_2 ((uint32_t)0x00000100) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP13 ((uint32_t)0x00000E00) /*!< SMP13[2:0] bits (Channel 13 Sample time selection) */ +#define ADC_SMPR1_SMP13_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define ADC_SMPR1_SMP13_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define ADC_SMPR1_SMP13_2 ((uint32_t)0x00000800) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP14 ((uint32_t)0x00007000) /*!< SMP14[2:0] bits (Channel 14 Sample time selection) */ +#define ADC_SMPR1_SMP14_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP14_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP14_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP15 ((uint32_t)0x00038000) /*!< SMP15[2:0] bits (Channel 15 Sample time selection) */ +#define ADC_SMPR1_SMP15_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP15_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP15_2 ((uint32_t)0x00020000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP16 ((uint32_t)0x001C0000) /*!< SMP16[2:0] bits (Channel 16 Sample time selection) */ +#define ADC_SMPR1_SMP16_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP16_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP16_2 ((uint32_t)0x00100000) /*!< Bit 2 */ + +#define ADC_SMPR1_SMP17 ((uint32_t)0x00E00000) /*!< SMP17[2:0] bits (Channel 17 Sample time selection) */ +#define ADC_SMPR1_SMP17_0 ((uint32_t)0x00200000) /*!< Bit 0 */ +#define ADC_SMPR1_SMP17_1 ((uint32_t)0x00400000) /*!< Bit 1 */ +#define ADC_SMPR1_SMP17_2 ((uint32_t)0x00800000) /*!< Bit 2 */ + +/****************** Bit definition for ADC_SMPR2 register *******************/ +#define ADC_SMPR2_SMP0 ((uint32_t)0x00000007) /*!< SMP0[2:0] bits (Channel 0 Sample time selection) */ +#define ADC_SMPR2_SMP0_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SMPR2_SMP0_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SMPR2_SMP0_2 ((uint32_t)0x00000004) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP1 ((uint32_t)0x00000038) /*!< SMP1[2:0] bits (Channel 1 Sample time selection) */ +#define ADC_SMPR2_SMP1_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define ADC_SMPR2_SMP1_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define ADC_SMPR2_SMP1_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP2 ((uint32_t)0x000001C0) /*!< SMP2[2:0] bits (Channel 2 Sample time selection) */ +#define ADC_SMPR2_SMP2_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define ADC_SMPR2_SMP2_1 ((uint32_t)0x00000080) /*!< Bit 1 */ +#define ADC_SMPR2_SMP2_2 ((uint32_t)0x00000100) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP3 ((uint32_t)0x00000E00) /*!< SMP3[2:0] bits (Channel 3 Sample time selection) */ +#define ADC_SMPR2_SMP3_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define ADC_SMPR2_SMP3_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define ADC_SMPR2_SMP3_2 ((uint32_t)0x00000800) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP4 ((uint32_t)0x00007000) /*!< SMP4[2:0] bits (Channel 4 Sample time selection) */ +#define ADC_SMPR2_SMP4_0 ((uint32_t)0x00001000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP4_1 ((uint32_t)0x00002000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP4_2 ((uint32_t)0x00004000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP5 ((uint32_t)0x00038000) /*!< SMP5[2:0] bits (Channel 5 Sample time selection) */ +#define ADC_SMPR2_SMP5_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP5_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP5_2 ((uint32_t)0x00020000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP6 ((uint32_t)0x001C0000) /*!< SMP6[2:0] bits (Channel 6 Sample time selection) */ +#define ADC_SMPR2_SMP6_0 ((uint32_t)0x00040000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP6_1 ((uint32_t)0x00080000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP6_2 ((uint32_t)0x00100000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP7 ((uint32_t)0x00E00000) /*!< SMP7[2:0] bits (Channel 7 Sample time selection) */ +#define ADC_SMPR2_SMP7_0 ((uint32_t)0x00200000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP7_1 ((uint32_t)0x00400000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP7_2 ((uint32_t)0x00800000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP8 ((uint32_t)0x07000000) /*!< SMP8[2:0] bits (Channel 8 Sample time selection) */ +#define ADC_SMPR2_SMP8_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP8_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP8_2 ((uint32_t)0x04000000) /*!< Bit 2 */ + +#define ADC_SMPR2_SMP9 ((uint32_t)0x38000000) /*!< SMP9[2:0] bits (Channel 9 Sample time selection) */ +#define ADC_SMPR2_SMP9_0 ((uint32_t)0x08000000) /*!< Bit 0 */ +#define ADC_SMPR2_SMP9_1 ((uint32_t)0x10000000) /*!< Bit 1 */ +#define ADC_SMPR2_SMP9_2 ((uint32_t)0x20000000) /*!< Bit 2 */ + +/****************** Bit definition for ADC_JOFR1 register *******************/ +#define ADC_JOFR1_JOFFSET1 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 1 */ + +/****************** Bit definition for ADC_JOFR2 register *******************/ +#define ADC_JOFR2_JOFFSET2 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 2 */ + +/****************** Bit definition for ADC_JOFR3 register *******************/ +#define ADC_JOFR3_JOFFSET3 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 3 */ + +/****************** Bit definition for ADC_JOFR4 register *******************/ +#define ADC_JOFR4_JOFFSET4 ((uint16_t)0x0FFF) /*!< Data offset for injected channel 4 */ + +/******************* Bit definition for ADC_HTR register ********************/ +#define ADC_HTR_HT ((uint16_t)0x0FFF) /*!< Analog watchdog high threshold */ + +/******************* Bit definition for ADC_LTR register ********************/ +#define ADC_LTR_LT ((uint16_t)0x0FFF) /*!< Analog watchdog low threshold */ + +/******************* Bit definition for ADC_SQR1 register *******************/ +#define ADC_SQR1_SQ13 ((uint32_t)0x0000001F) /*!< SQ13[4:0] bits (13th conversion in regular sequence) */ +#define ADC_SQR1_SQ13_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR1_SQ13_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR1_SQ13_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR1_SQ13_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR1_SQ13_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR1_SQ14 ((uint32_t)0x000003E0) /*!< SQ14[4:0] bits (14th conversion in regular sequence) */ +#define ADC_SQR1_SQ14_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR1_SQ14_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR1_SQ14_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR1_SQ14_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR1_SQ14_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR1_SQ15 ((uint32_t)0x00007C00) /*!< SQ15[4:0] bits (15th conversion in regular sequence) */ +#define ADC_SQR1_SQ15_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR1_SQ15_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR1_SQ15_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR1_SQ15_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR1_SQ15_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR1_SQ16 ((uint32_t)0x000F8000) /*!< SQ16[4:0] bits (16th conversion in regular sequence) */ +#define ADC_SQR1_SQ16_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR1_SQ16_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR1_SQ16_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR1_SQ16_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR1_SQ16_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR1_L ((uint32_t)0x00F00000) /*!< L[3:0] bits (Regular channel sequence length) */ +#define ADC_SQR1_L_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR1_L_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR1_L_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR1_L_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +/******************* Bit definition for ADC_SQR2 register *******************/ +#define ADC_SQR2_SQ7 ((uint32_t)0x0000001F) /*!< SQ7[4:0] bits (7th conversion in regular sequence) */ +#define ADC_SQR2_SQ7_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR2_SQ7_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR2_SQ7_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR2_SQ7_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR2_SQ7_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR2_SQ8 ((uint32_t)0x000003E0) /*!< SQ8[4:0] bits (8th conversion in regular sequence) */ +#define ADC_SQR2_SQ8_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR2_SQ8_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR2_SQ8_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR2_SQ8_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR2_SQ8_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR2_SQ9 ((uint32_t)0x00007C00) /*!< SQ9[4:0] bits (9th conversion in regular sequence) */ +#define ADC_SQR2_SQ9_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR2_SQ9_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR2_SQ9_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR2_SQ9_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR2_SQ9_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ10 ((uint32_t)0x000F8000) /*!< SQ10[4:0] bits (10th conversion in regular sequence) */ +#define ADC_SQR2_SQ10_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR2_SQ10_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR2_SQ10_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR2_SQ10_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR2_SQ10_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ11 ((uint32_t)0x01F00000) /*!< SQ11[4:0] bits (11th conversion in regular sequence) */ +#define ADC_SQR2_SQ11_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR2_SQ11_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR2_SQ11_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR2_SQ11_3 ((uint32_t)0x00800000) /*!< Bit 3 */ +#define ADC_SQR2_SQ11_4 ((uint32_t)0x01000000) /*!< Bit 4 */ + +#define ADC_SQR2_SQ12 ((uint32_t)0x3E000000) /*!< SQ12[4:0] bits (12th conversion in regular sequence) */ +#define ADC_SQR2_SQ12_0 ((uint32_t)0x02000000) /*!< Bit 0 */ +#define ADC_SQR2_SQ12_1 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define ADC_SQR2_SQ12_2 ((uint32_t)0x08000000) /*!< Bit 2 */ +#define ADC_SQR2_SQ12_3 ((uint32_t)0x10000000) /*!< Bit 3 */ +#define ADC_SQR2_SQ12_4 ((uint32_t)0x20000000) /*!< Bit 4 */ + +/******************* Bit definition for ADC_SQR3 register *******************/ +#define ADC_SQR3_SQ1 ((uint32_t)0x0000001F) /*!< SQ1[4:0] bits (1st conversion in regular sequence) */ +#define ADC_SQR3_SQ1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_SQR3_SQ1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_SQR3_SQ1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_SQR3_SQ1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_SQR3_SQ1_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_SQR3_SQ2 ((uint32_t)0x000003E0) /*!< SQ2[4:0] bits (2nd conversion in regular sequence) */ +#define ADC_SQR3_SQ2_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_SQR3_SQ2_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_SQR3_SQ2_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_SQR3_SQ2_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_SQR3_SQ2_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_SQR3_SQ3 ((uint32_t)0x00007C00) /*!< SQ3[4:0] bits (3rd conversion in regular sequence) */ +#define ADC_SQR3_SQ3_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_SQR3_SQ3_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_SQR3_SQ3_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_SQR3_SQ3_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_SQR3_SQ3_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ4 ((uint32_t)0x000F8000) /*!< SQ4[4:0] bits (4th conversion in regular sequence) */ +#define ADC_SQR3_SQ4_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_SQR3_SQ4_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_SQR3_SQ4_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_SQR3_SQ4_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_SQR3_SQ4_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ5 ((uint32_t)0x01F00000) /*!< SQ5[4:0] bits (5th conversion in regular sequence) */ +#define ADC_SQR3_SQ5_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_SQR3_SQ5_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define ADC_SQR3_SQ5_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define ADC_SQR3_SQ5_3 ((uint32_t)0x00800000) /*!< Bit 3 */ +#define ADC_SQR3_SQ5_4 ((uint32_t)0x01000000) /*!< Bit 4 */ + +#define ADC_SQR3_SQ6 ((uint32_t)0x3E000000) /*!< SQ6[4:0] bits (6th conversion in regular sequence) */ +#define ADC_SQR3_SQ6_0 ((uint32_t)0x02000000) /*!< Bit 0 */ +#define ADC_SQR3_SQ6_1 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define ADC_SQR3_SQ6_2 ((uint32_t)0x08000000) /*!< Bit 2 */ +#define ADC_SQR3_SQ6_3 ((uint32_t)0x10000000) /*!< Bit 3 */ +#define ADC_SQR3_SQ6_4 ((uint32_t)0x20000000) /*!< Bit 4 */ + +/******************* Bit definition for ADC_JSQR register *******************/ +#define ADC_JSQR_JSQ1 ((uint32_t)0x0000001F) /*!< JSQ1[4:0] bits (1st conversion in injected sequence) */ +#define ADC_JSQR_JSQ1_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define ADC_JSQR_JSQ1_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define ADC_JSQR_JSQ1_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define ADC_JSQR_JSQ1_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define ADC_JSQR_JSQ1_4 ((uint32_t)0x00000010) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ2 ((uint32_t)0x000003E0) /*!< JSQ2[4:0] bits (2nd conversion in injected sequence) */ +#define ADC_JSQR_JSQ2_0 ((uint32_t)0x00000020) /*!< Bit 0 */ +#define ADC_JSQR_JSQ2_1 ((uint32_t)0x00000040) /*!< Bit 1 */ +#define ADC_JSQR_JSQ2_2 ((uint32_t)0x00000080) /*!< Bit 2 */ +#define ADC_JSQR_JSQ2_3 ((uint32_t)0x00000100) /*!< Bit 3 */ +#define ADC_JSQR_JSQ2_4 ((uint32_t)0x00000200) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ3 ((uint32_t)0x00007C00) /*!< JSQ3[4:0] bits (3rd conversion in injected sequence) */ +#define ADC_JSQR_JSQ3_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define ADC_JSQR_JSQ3_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define ADC_JSQR_JSQ3_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define ADC_JSQR_JSQ3_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define ADC_JSQR_JSQ3_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define ADC_JSQR_JSQ4 ((uint32_t)0x000F8000) /*!< JSQ4[4:0] bits (4th conversion in injected sequence) */ +#define ADC_JSQR_JSQ4_0 ((uint32_t)0x00008000) /*!< Bit 0 */ +#define ADC_JSQR_JSQ4_1 ((uint32_t)0x00010000) /*!< Bit 1 */ +#define ADC_JSQR_JSQ4_2 ((uint32_t)0x00020000) /*!< Bit 2 */ +#define ADC_JSQR_JSQ4_3 ((uint32_t)0x00040000) /*!< Bit 3 */ +#define ADC_JSQR_JSQ4_4 ((uint32_t)0x00080000) /*!< Bit 4 */ + +#define ADC_JSQR_JL ((uint32_t)0x00300000) /*!< JL[1:0] bits (Injected Sequence length) */ +#define ADC_JSQR_JL_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define ADC_JSQR_JL_1 ((uint32_t)0x00200000) /*!< Bit 1 */ + +/******************* Bit definition for ADC_JDR1 register *******************/ +#define ADC_JDR1_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR2 register *******************/ +#define ADC_JDR2_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR3 register *******************/ +#define ADC_JDR3_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************* Bit definition for ADC_JDR4 register *******************/ +#define ADC_JDR4_JDATA ((uint16_t)0xFFFF) /*!< Injected data */ + +/******************** Bit definition for ADC_DR register ********************/ +#define ADC_DR_DATA ((uint32_t)0x0000FFFF) /*!< Regular data */ +#define ADC_DR_ADC2DATA ((uint32_t)0xFFFF0000) /*!< ADC2 data */ + +/******************************************************************************/ +/* */ +/* Digital to Analog Converter */ +/* */ +/******************************************************************************/ + +/******************** Bit definition for DAC_CR register ********************/ +#define DAC_CR_EN1 ((uint32_t)0x00000001) /*!< DAC channel1 enable */ +#define DAC_CR_BOFF1 ((uint32_t)0x00000002) /*!< DAC channel1 output buffer disable */ +#define DAC_CR_TEN1 ((uint32_t)0x00000004) /*!< DAC channel1 Trigger enable */ + +#define DAC_CR_TSEL1 ((uint32_t)0x00000038) /*!< TSEL1[2:0] (DAC channel1 Trigger selection) */ +#define DAC_CR_TSEL1_0 ((uint32_t)0x00000008) /*!< Bit 0 */ +#define DAC_CR_TSEL1_1 ((uint32_t)0x00000010) /*!< Bit 1 */ +#define DAC_CR_TSEL1_2 ((uint32_t)0x00000020) /*!< Bit 2 */ + +#define DAC_CR_WAVE1 ((uint32_t)0x000000C0) /*!< WAVE1[1:0] (DAC channel1 noise/triangle wave generation enable) */ +#define DAC_CR_WAVE1_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define DAC_CR_WAVE1_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define DAC_CR_MAMP1 ((uint32_t)0x00000F00) /*!< MAMP1[3:0] (DAC channel1 Mask/Amplitude selector) */ +#define DAC_CR_MAMP1_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define DAC_CR_MAMP1_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define DAC_CR_MAMP1_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define DAC_CR_MAMP1_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define DAC_CR_DMAEN1 ((uint32_t)0x00001000) /*!< DAC channel1 DMA enable */ +#define DAC_CR_EN2 ((uint32_t)0x00010000) /*!< DAC channel2 enable */ +#define DAC_CR_BOFF2 ((uint32_t)0x00020000) /*!< DAC channel2 output buffer disable */ +#define DAC_CR_TEN2 ((uint32_t)0x00040000) /*!< DAC channel2 Trigger enable */ + +#define DAC_CR_TSEL2 ((uint32_t)0x00380000) /*!< TSEL2[2:0] (DAC channel2 Trigger selection) */ +#define DAC_CR_TSEL2_0 ((uint32_t)0x00080000) /*!< Bit 0 */ +#define DAC_CR_TSEL2_1 ((uint32_t)0x00100000) /*!< Bit 1 */ +#define DAC_CR_TSEL2_2 ((uint32_t)0x00200000) /*!< Bit 2 */ + +#define DAC_CR_WAVE2 ((uint32_t)0x00C00000) /*!< WAVE2[1:0] (DAC channel2 noise/triangle wave generation enable) */ +#define DAC_CR_WAVE2_0 ((uint32_t)0x00400000) /*!< Bit 0 */ +#define DAC_CR_WAVE2_1 ((uint32_t)0x00800000) /*!< Bit 1 */ + +#define DAC_CR_MAMP2 ((uint32_t)0x0F000000) /*!< MAMP2[3:0] (DAC channel2 Mask/Amplitude selector) */ +#define DAC_CR_MAMP2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define DAC_CR_MAMP2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define DAC_CR_MAMP2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define DAC_CR_MAMP2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define DAC_CR_DMAEN2 ((uint32_t)0x10000000) /*!< DAC channel2 DMA enabled */ + +/***************** Bit definition for DAC_SWTRIGR register ******************/ +#define DAC_SWTRIGR_SWTRIG1 ((uint8_t)0x01) /*!< DAC channel1 software trigger */ +#define DAC_SWTRIGR_SWTRIG2 ((uint8_t)0x02) /*!< DAC channel2 software trigger */ + +/***************** Bit definition for DAC_DHR12R1 register ******************/ +#define DAC_DHR12R1_DACC1DHR ((uint16_t)0x0FFF) /*!< DAC channel1 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12L1 register ******************/ +#define DAC_DHR12L1_DACC1DHR ((uint16_t)0xFFF0) /*!< DAC channel1 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8R1 register ******************/ +#define DAC_DHR8R1_DACC1DHR ((uint8_t)0xFF) /*!< DAC channel1 8-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12R2 register ******************/ +#define DAC_DHR12R2_DACC2DHR ((uint16_t)0x0FFF) /*!< DAC channel2 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12L2 register ******************/ +#define DAC_DHR12L2_DACC2DHR ((uint16_t)0xFFF0) /*!< DAC channel2 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8R2 register ******************/ +#define DAC_DHR8R2_DACC2DHR ((uint8_t)0xFF) /*!< DAC channel2 8-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12RD register ******************/ +#define DAC_DHR12RD_DACC1DHR ((uint32_t)0x00000FFF) /*!< DAC channel1 12-bit Right aligned data */ +#define DAC_DHR12RD_DACC2DHR ((uint32_t)0x0FFF0000) /*!< DAC channel2 12-bit Right aligned data */ + +/***************** Bit definition for DAC_DHR12LD register ******************/ +#define DAC_DHR12LD_DACC1DHR ((uint32_t)0x0000FFF0) /*!< DAC channel1 12-bit Left aligned data */ +#define DAC_DHR12LD_DACC2DHR ((uint32_t)0xFFF00000) /*!< DAC channel2 12-bit Left aligned data */ + +/****************** Bit definition for DAC_DHR8RD register ******************/ +#define DAC_DHR8RD_DACC1DHR ((uint16_t)0x00FF) /*!< DAC channel1 8-bit Right aligned data */ +#define DAC_DHR8RD_DACC2DHR ((uint16_t)0xFF00) /*!< DAC channel2 8-bit Right aligned data */ + +/******************* Bit definition for DAC_DOR1 register *******************/ +#define DAC_DOR1_DACC1DOR ((uint16_t)0x0FFF) /*!< DAC channel1 data output */ + +/******************* Bit definition for DAC_DOR2 register *******************/ +#define DAC_DOR2_DACC2DOR ((uint16_t)0x0FFF) /*!< DAC channel2 data output */ + +/******************** Bit definition for DAC_SR register ********************/ +#define DAC_SR_DMAUDR1 ((uint32_t)0x00002000) /*!< DAC channel1 DMA underrun flag */ +#define DAC_SR_DMAUDR2 ((uint32_t)0x20000000) /*!< DAC channel2 DMA underrun flag */ + +/******************************************************************************/ +/* */ +/* CEC */ +/* */ +/******************************************************************************/ +/******************** Bit definition for CEC_CFGR register ******************/ +#define CEC_CFGR_PE ((uint16_t)0x0001) /*!< Peripheral Enable */ +#define CEC_CFGR_IE ((uint16_t)0x0002) /*!< Interrupt Enable */ +#define CEC_CFGR_BTEM ((uint16_t)0x0004) /*!< Bit Timing Error Mode */ +#define CEC_CFGR_BPEM ((uint16_t)0x0008) /*!< Bit Period Error Mode */ + +/******************** Bit definition for CEC_OAR register ******************/ +#define CEC_OAR_OA ((uint16_t)0x000F) /*!< OA[3:0]: Own Address */ +#define CEC_OAR_OA_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define CEC_OAR_OA_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define CEC_OAR_OA_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define CEC_OAR_OA_3 ((uint16_t)0x0008) /*!< Bit 3 */ + +/******************** Bit definition for CEC_PRES register ******************/ +#define CEC_PRES_PRES ((uint16_t)0x3FFF) /*!< Prescaler Counter Value */ + +/******************** Bit definition for CEC_ESR register ******************/ +#define CEC_ESR_BTE ((uint16_t)0x0001) /*!< Bit Timing Error */ +#define CEC_ESR_BPE ((uint16_t)0x0002) /*!< Bit Period Error */ +#define CEC_ESR_RBTFE ((uint16_t)0x0004) /*!< Rx Block Transfer Finished Error */ +#define CEC_ESR_SBE ((uint16_t)0x0008) /*!< Start Bit Error */ +#define CEC_ESR_ACKE ((uint16_t)0x0010) /*!< Block Acknowledge Error */ +#define CEC_ESR_LINE ((uint16_t)0x0020) /*!< Line Error */ +#define CEC_ESR_TBTFE ((uint16_t)0x0040) /*!< Tx Block Transfer Finished Error */ + +/******************** Bit definition for CEC_CSR register ******************/ +#define CEC_CSR_TSOM ((uint16_t)0x0001) /*!< Tx Start Of Message */ +#define CEC_CSR_TEOM ((uint16_t)0x0002) /*!< Tx End Of Message */ +#define CEC_CSR_TERR ((uint16_t)0x0004) /*!< Tx Error */ +#define CEC_CSR_TBTRF ((uint16_t)0x0008) /*!< Tx Byte Transfer Request or Block Transfer Finished */ +#define CEC_CSR_RSOM ((uint16_t)0x0010) /*!< Rx Start Of Message */ +#define CEC_CSR_REOM ((uint16_t)0x0020) /*!< Rx End Of Message */ +#define CEC_CSR_RERR ((uint16_t)0x0040) /*!< Rx Error */ +#define CEC_CSR_RBTF ((uint16_t)0x0080) /*!< Rx Block Transfer Finished */ + +/******************** Bit definition for CEC_TXD register ******************/ +#define CEC_TXD_TXD ((uint16_t)0x00FF) /*!< Tx Data register */ + +/******************** Bit definition for CEC_RXD register ******************/ +#define CEC_RXD_RXD ((uint16_t)0x00FF) /*!< Rx Data register */ + +/******************************************************************************/ +/* */ +/* TIM */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for TIM_CR1 register ********************/ +#define TIM_CR1_CEN ((uint16_t)0x0001) /*!< Counter enable */ +#define TIM_CR1_UDIS ((uint16_t)0x0002) /*!< Update disable */ +#define TIM_CR1_URS ((uint16_t)0x0004) /*!< Update request source */ +#define TIM_CR1_OPM ((uint16_t)0x0008) /*!< One pulse mode */ +#define TIM_CR1_DIR ((uint16_t)0x0010) /*!< Direction */ + +#define TIM_CR1_CMS ((uint16_t)0x0060) /*!< CMS[1:0] bits (Center-aligned mode selection) */ +#define TIM_CR1_CMS_0 ((uint16_t)0x0020) /*!< Bit 0 */ +#define TIM_CR1_CMS_1 ((uint16_t)0x0040) /*!< Bit 1 */ + +#define TIM_CR1_ARPE ((uint16_t)0x0080) /*!< Auto-reload preload enable */ + +#define TIM_CR1_CKD ((uint16_t)0x0300) /*!< CKD[1:0] bits (clock division) */ +#define TIM_CR1_CKD_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CR1_CKD_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +/******************* Bit definition for TIM_CR2 register ********************/ +#define TIM_CR2_CCPC ((uint16_t)0x0001) /*!< Capture/Compare Preloaded Control */ +#define TIM_CR2_CCUS ((uint16_t)0x0004) /*!< Capture/Compare Control Update Selection */ +#define TIM_CR2_CCDS ((uint16_t)0x0008) /*!< Capture/Compare DMA Selection */ + +#define TIM_CR2_MMS ((uint16_t)0x0070) /*!< MMS[2:0] bits (Master Mode Selection) */ +#define TIM_CR2_MMS_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CR2_MMS_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CR2_MMS_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CR2_TI1S ((uint16_t)0x0080) /*!< TI1 Selection */ +#define TIM_CR2_OIS1 ((uint16_t)0x0100) /*!< Output Idle state 1 (OC1 output) */ +#define TIM_CR2_OIS1N ((uint16_t)0x0200) /*!< Output Idle state 1 (OC1N output) */ +#define TIM_CR2_OIS2 ((uint16_t)0x0400) /*!< Output Idle state 2 (OC2 output) */ +#define TIM_CR2_OIS2N ((uint16_t)0x0800) /*!< Output Idle state 2 (OC2N output) */ +#define TIM_CR2_OIS3 ((uint16_t)0x1000) /*!< Output Idle state 3 (OC3 output) */ +#define TIM_CR2_OIS3N ((uint16_t)0x2000) /*!< Output Idle state 3 (OC3N output) */ +#define TIM_CR2_OIS4 ((uint16_t)0x4000) /*!< Output Idle state 4 (OC4 output) */ + +/******************* Bit definition for TIM_SMCR register *******************/ +#define TIM_SMCR_SMS ((uint16_t)0x0007) /*!< SMS[2:0] bits (Slave mode selection) */ +#define TIM_SMCR_SMS_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_SMCR_SMS_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_SMCR_SMS_2 ((uint16_t)0x0004) /*!< Bit 2 */ + +#define TIM_SMCR_TS ((uint16_t)0x0070) /*!< TS[2:0] bits (Trigger selection) */ +#define TIM_SMCR_TS_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_SMCR_TS_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_SMCR_TS_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_SMCR_MSM ((uint16_t)0x0080) /*!< Master/slave mode */ + +#define TIM_SMCR_ETF ((uint16_t)0x0F00) /*!< ETF[3:0] bits (External trigger filter) */ +#define TIM_SMCR_ETF_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_SMCR_ETF_1 ((uint16_t)0x0200) /*!< Bit 1 */ +#define TIM_SMCR_ETF_2 ((uint16_t)0x0400) /*!< Bit 2 */ +#define TIM_SMCR_ETF_3 ((uint16_t)0x0800) /*!< Bit 3 */ + +#define TIM_SMCR_ETPS ((uint16_t)0x3000) /*!< ETPS[1:0] bits (External trigger prescaler) */ +#define TIM_SMCR_ETPS_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_SMCR_ETPS_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define TIM_SMCR_ECE ((uint16_t)0x4000) /*!< External clock enable */ +#define TIM_SMCR_ETP ((uint16_t)0x8000) /*!< External trigger polarity */ + +/******************* Bit definition for TIM_DIER register *******************/ +#define TIM_DIER_UIE ((uint16_t)0x0001) /*!< Update interrupt enable */ +#define TIM_DIER_CC1IE ((uint16_t)0x0002) /*!< Capture/Compare 1 interrupt enable */ +#define TIM_DIER_CC2IE ((uint16_t)0x0004) /*!< Capture/Compare 2 interrupt enable */ +#define TIM_DIER_CC3IE ((uint16_t)0x0008) /*!< Capture/Compare 3 interrupt enable */ +#define TIM_DIER_CC4IE ((uint16_t)0x0010) /*!< Capture/Compare 4 interrupt enable */ +#define TIM_DIER_COMIE ((uint16_t)0x0020) /*!< COM interrupt enable */ +#define TIM_DIER_TIE ((uint16_t)0x0040) /*!< Trigger interrupt enable */ +#define TIM_DIER_BIE ((uint16_t)0x0080) /*!< Break interrupt enable */ +#define TIM_DIER_UDE ((uint16_t)0x0100) /*!< Update DMA request enable */ +#define TIM_DIER_CC1DE ((uint16_t)0x0200) /*!< Capture/Compare 1 DMA request enable */ +#define TIM_DIER_CC2DE ((uint16_t)0x0400) /*!< Capture/Compare 2 DMA request enable */ +#define TIM_DIER_CC3DE ((uint16_t)0x0800) /*!< Capture/Compare 3 DMA request enable */ +#define TIM_DIER_CC4DE ((uint16_t)0x1000) /*!< Capture/Compare 4 DMA request enable */ +#define TIM_DIER_COMDE ((uint16_t)0x2000) /*!< COM DMA request enable */ +#define TIM_DIER_TDE ((uint16_t)0x4000) /*!< Trigger DMA request enable */ + +/******************** Bit definition for TIM_SR register ********************/ +#define TIM_SR_UIF ((uint16_t)0x0001) /*!< Update interrupt Flag */ +#define TIM_SR_CC1IF ((uint16_t)0x0002) /*!< Capture/Compare 1 interrupt Flag */ +#define TIM_SR_CC2IF ((uint16_t)0x0004) /*!< Capture/Compare 2 interrupt Flag */ +#define TIM_SR_CC3IF ((uint16_t)0x0008) /*!< Capture/Compare 3 interrupt Flag */ +#define TIM_SR_CC4IF ((uint16_t)0x0010) /*!< Capture/Compare 4 interrupt Flag */ +#define TIM_SR_COMIF ((uint16_t)0x0020) /*!< COM interrupt Flag */ +#define TIM_SR_TIF ((uint16_t)0x0040) /*!< Trigger interrupt Flag */ +#define TIM_SR_BIF ((uint16_t)0x0080) /*!< Break interrupt Flag */ +#define TIM_SR_CC1OF ((uint16_t)0x0200) /*!< Capture/Compare 1 Overcapture Flag */ +#define TIM_SR_CC2OF ((uint16_t)0x0400) /*!< Capture/Compare 2 Overcapture Flag */ +#define TIM_SR_CC3OF ((uint16_t)0x0800) /*!< Capture/Compare 3 Overcapture Flag */ +#define TIM_SR_CC4OF ((uint16_t)0x1000) /*!< Capture/Compare 4 Overcapture Flag */ + +/******************* Bit definition for TIM_EGR register ********************/ +#define TIM_EGR_UG ((uint8_t)0x01) /*!< Update Generation */ +#define TIM_EGR_CC1G ((uint8_t)0x02) /*!< Capture/Compare 1 Generation */ +#define TIM_EGR_CC2G ((uint8_t)0x04) /*!< Capture/Compare 2 Generation */ +#define TIM_EGR_CC3G ((uint8_t)0x08) /*!< Capture/Compare 3 Generation */ +#define TIM_EGR_CC4G ((uint8_t)0x10) /*!< Capture/Compare 4 Generation */ +#define TIM_EGR_COMG ((uint8_t)0x20) /*!< Capture/Compare Control Update Generation */ +#define TIM_EGR_TG ((uint8_t)0x40) /*!< Trigger Generation */ +#define TIM_EGR_BG ((uint8_t)0x80) /*!< Break Generation */ + +/****************** Bit definition for TIM_CCMR1 register *******************/ +#define TIM_CCMR1_CC1S ((uint16_t)0x0003) /*!< CC1S[1:0] bits (Capture/Compare 1 Selection) */ +#define TIM_CCMR1_CC1S_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_CCMR1_CC1S_1 ((uint16_t)0x0002) /*!< Bit 1 */ + +#define TIM_CCMR1_OC1FE ((uint16_t)0x0004) /*!< Output Compare 1 Fast enable */ +#define TIM_CCMR1_OC1PE ((uint16_t)0x0008) /*!< Output Compare 1 Preload enable */ + +#define TIM_CCMR1_OC1M ((uint16_t)0x0070) /*!< OC1M[2:0] bits (Output Compare 1 Mode) */ +#define TIM_CCMR1_OC1M_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR1_OC1M_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR1_OC1M_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CCMR1_OC1CE ((uint16_t)0x0080) /*!< Output Compare 1Clear Enable */ + +#define TIM_CCMR1_CC2S ((uint16_t)0x0300) /*!< CC2S[1:0] bits (Capture/Compare 2 Selection) */ +#define TIM_CCMR1_CC2S_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CCMR1_CC2S_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_CCMR1_OC2FE ((uint16_t)0x0400) /*!< Output Compare 2 Fast enable */ +#define TIM_CCMR1_OC2PE ((uint16_t)0x0800) /*!< Output Compare 2 Preload enable */ + +#define TIM_CCMR1_OC2M ((uint16_t)0x7000) /*!< OC2M[2:0] bits (Output Compare 2 Mode) */ +#define TIM_CCMR1_OC2M_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR1_OC2M_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR1_OC2M_2 ((uint16_t)0x4000) /*!< Bit 2 */ + +#define TIM_CCMR1_OC2CE ((uint16_t)0x8000) /*!< Output Compare 2 Clear Enable */ + +/*----------------------------------------------------------------------------*/ + +#define TIM_CCMR1_IC1PSC ((uint16_t)0x000C) /*!< IC1PSC[1:0] bits (Input Capture 1 Prescaler) */ +#define TIM_CCMR1_IC1PSC_0 ((uint16_t)0x0004) /*!< Bit 0 */ +#define TIM_CCMR1_IC1PSC_1 ((uint16_t)0x0008) /*!< Bit 1 */ + +#define TIM_CCMR1_IC1F ((uint16_t)0x00F0) /*!< IC1F[3:0] bits (Input Capture 1 Filter) */ +#define TIM_CCMR1_IC1F_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR1_IC1F_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR1_IC1F_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define TIM_CCMR1_IC1F_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define TIM_CCMR1_IC2PSC ((uint16_t)0x0C00) /*!< IC2PSC[1:0] bits (Input Capture 2 Prescaler) */ +#define TIM_CCMR1_IC2PSC_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define TIM_CCMR1_IC2PSC_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define TIM_CCMR1_IC2F ((uint16_t)0xF000) /*!< IC2F[3:0] bits (Input Capture 2 Filter) */ +#define TIM_CCMR1_IC2F_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR1_IC2F_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR1_IC2F_2 ((uint16_t)0x4000) /*!< Bit 2 */ +#define TIM_CCMR1_IC2F_3 ((uint16_t)0x8000) /*!< Bit 3 */ + +/****************** Bit definition for TIM_CCMR2 register *******************/ +#define TIM_CCMR2_CC3S ((uint16_t)0x0003) /*!< CC3S[1:0] bits (Capture/Compare 3 Selection) */ +#define TIM_CCMR2_CC3S_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_CCMR2_CC3S_1 ((uint16_t)0x0002) /*!< Bit 1 */ + +#define TIM_CCMR2_OC3FE ((uint16_t)0x0004) /*!< Output Compare 3 Fast enable */ +#define TIM_CCMR2_OC3PE ((uint16_t)0x0008) /*!< Output Compare 3 Preload enable */ + +#define TIM_CCMR2_OC3M ((uint16_t)0x0070) /*!< OC3M[2:0] bits (Output Compare 3 Mode) */ +#define TIM_CCMR2_OC3M_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR2_OC3M_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR2_OC3M_2 ((uint16_t)0x0040) /*!< Bit 2 */ + +#define TIM_CCMR2_OC3CE ((uint16_t)0x0080) /*!< Output Compare 3 Clear Enable */ + +#define TIM_CCMR2_CC4S ((uint16_t)0x0300) /*!< CC4S[1:0] bits (Capture/Compare 4 Selection) */ +#define TIM_CCMR2_CC4S_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_CCMR2_CC4S_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_CCMR2_OC4FE ((uint16_t)0x0400) /*!< Output Compare 4 Fast enable */ +#define TIM_CCMR2_OC4PE ((uint16_t)0x0800) /*!< Output Compare 4 Preload enable */ + +#define TIM_CCMR2_OC4M ((uint16_t)0x7000) /*!< OC4M[2:0] bits (Output Compare 4 Mode) */ +#define TIM_CCMR2_OC4M_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR2_OC4M_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR2_OC4M_2 ((uint16_t)0x4000) /*!< Bit 2 */ + +#define TIM_CCMR2_OC4CE ((uint16_t)0x8000) /*!< Output Compare 4 Clear Enable */ + +/*----------------------------------------------------------------------------*/ + +#define TIM_CCMR2_IC3PSC ((uint16_t)0x000C) /*!< IC3PSC[1:0] bits (Input Capture 3 Prescaler) */ +#define TIM_CCMR2_IC3PSC_0 ((uint16_t)0x0004) /*!< Bit 0 */ +#define TIM_CCMR2_IC3PSC_1 ((uint16_t)0x0008) /*!< Bit 1 */ + +#define TIM_CCMR2_IC3F ((uint16_t)0x00F0) /*!< IC3F[3:0] bits (Input Capture 3 Filter) */ +#define TIM_CCMR2_IC3F_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define TIM_CCMR2_IC3F_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define TIM_CCMR2_IC3F_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define TIM_CCMR2_IC3F_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define TIM_CCMR2_IC4PSC ((uint16_t)0x0C00) /*!< IC4PSC[1:0] bits (Input Capture 4 Prescaler) */ +#define TIM_CCMR2_IC4PSC_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define TIM_CCMR2_IC4PSC_1 ((uint16_t)0x0800) /*!< Bit 1 */ + +#define TIM_CCMR2_IC4F ((uint16_t)0xF000) /*!< IC4F[3:0] bits (Input Capture 4 Filter) */ +#define TIM_CCMR2_IC4F_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define TIM_CCMR2_IC4F_1 ((uint16_t)0x2000) /*!< Bit 1 */ +#define TIM_CCMR2_IC4F_2 ((uint16_t)0x4000) /*!< Bit 2 */ +#define TIM_CCMR2_IC4F_3 ((uint16_t)0x8000) /*!< Bit 3 */ + +/******************* Bit definition for TIM_CCER register *******************/ +#define TIM_CCER_CC1E ((uint16_t)0x0001) /*!< Capture/Compare 1 output enable */ +#define TIM_CCER_CC1P ((uint16_t)0x0002) /*!< Capture/Compare 1 output Polarity */ +#define TIM_CCER_CC1NE ((uint16_t)0x0004) /*!< Capture/Compare 1 Complementary output enable */ +#define TIM_CCER_CC1NP ((uint16_t)0x0008) /*!< Capture/Compare 1 Complementary output Polarity */ +#define TIM_CCER_CC2E ((uint16_t)0x0010) /*!< Capture/Compare 2 output enable */ +#define TIM_CCER_CC2P ((uint16_t)0x0020) /*!< Capture/Compare 2 output Polarity */ +#define TIM_CCER_CC2NE ((uint16_t)0x0040) /*!< Capture/Compare 2 Complementary output enable */ +#define TIM_CCER_CC2NP ((uint16_t)0x0080) /*!< Capture/Compare 2 Complementary output Polarity */ +#define TIM_CCER_CC3E ((uint16_t)0x0100) /*!< Capture/Compare 3 output enable */ +#define TIM_CCER_CC3P ((uint16_t)0x0200) /*!< Capture/Compare 3 output Polarity */ +#define TIM_CCER_CC3NE ((uint16_t)0x0400) /*!< Capture/Compare 3 Complementary output enable */ +#define TIM_CCER_CC3NP ((uint16_t)0x0800) /*!< Capture/Compare 3 Complementary output Polarity */ +#define TIM_CCER_CC4E ((uint16_t)0x1000) /*!< Capture/Compare 4 output enable */ +#define TIM_CCER_CC4P ((uint16_t)0x2000) /*!< Capture/Compare 4 output Polarity */ +#define TIM_CCER_CC4NP ((uint16_t)0x8000) /*!< Capture/Compare 4 Complementary output Polarity */ + +/******************* Bit definition for TIM_CNT register ********************/ +#define TIM_CNT_CNT ((uint16_t)0xFFFF) /*!< Counter Value */ + +/******************* Bit definition for TIM_PSC register ********************/ +#define TIM_PSC_PSC ((uint16_t)0xFFFF) /*!< Prescaler Value */ + +/******************* Bit definition for TIM_ARR register ********************/ +#define TIM_ARR_ARR ((uint16_t)0xFFFF) /*!< actual auto-reload Value */ + +/******************* Bit definition for TIM_RCR register ********************/ +#define TIM_RCR_REP ((uint8_t)0xFF) /*!< Repetition Counter Value */ + +/******************* Bit definition for TIM_CCR1 register *******************/ +#define TIM_CCR1_CCR1 ((uint16_t)0xFFFF) /*!< Capture/Compare 1 Value */ + +/******************* Bit definition for TIM_CCR2 register *******************/ +#define TIM_CCR2_CCR2 ((uint16_t)0xFFFF) /*!< Capture/Compare 2 Value */ + +/******************* Bit definition for TIM_CCR3 register *******************/ +#define TIM_CCR3_CCR3 ((uint16_t)0xFFFF) /*!< Capture/Compare 3 Value */ + +/******************* Bit definition for TIM_CCR4 register *******************/ +#define TIM_CCR4_CCR4 ((uint16_t)0xFFFF) /*!< Capture/Compare 4 Value */ + +/******************* Bit definition for TIM_BDTR register *******************/ +#define TIM_BDTR_DTG ((uint16_t)0x00FF) /*!< DTG[0:7] bits (Dead-Time Generator set-up) */ +#define TIM_BDTR_DTG_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_BDTR_DTG_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_BDTR_DTG_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define TIM_BDTR_DTG_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define TIM_BDTR_DTG_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define TIM_BDTR_DTG_5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define TIM_BDTR_DTG_6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define TIM_BDTR_DTG_7 ((uint16_t)0x0080) /*!< Bit 7 */ + +#define TIM_BDTR_LOCK ((uint16_t)0x0300) /*!< LOCK[1:0] bits (Lock Configuration) */ +#define TIM_BDTR_LOCK_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_BDTR_LOCK_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define TIM_BDTR_OSSI ((uint16_t)0x0400) /*!< Off-State Selection for Idle mode */ +#define TIM_BDTR_OSSR ((uint16_t)0x0800) /*!< Off-State Selection for Run mode */ +#define TIM_BDTR_BKE ((uint16_t)0x1000) /*!< Break enable */ +#define TIM_BDTR_BKP ((uint16_t)0x2000) /*!< Break Polarity */ +#define TIM_BDTR_AOE ((uint16_t)0x4000) /*!< Automatic Output enable */ +#define TIM_BDTR_MOE ((uint16_t)0x8000) /*!< Main Output enable */ + +/******************* Bit definition for TIM_DCR register ********************/ +#define TIM_DCR_DBA ((uint16_t)0x001F) /*!< DBA[4:0] bits (DMA Base Address) */ +#define TIM_DCR_DBA_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define TIM_DCR_DBA_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define TIM_DCR_DBA_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define TIM_DCR_DBA_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define TIM_DCR_DBA_4 ((uint16_t)0x0010) /*!< Bit 4 */ + +#define TIM_DCR_DBL ((uint16_t)0x1F00) /*!< DBL[4:0] bits (DMA Burst Length) */ +#define TIM_DCR_DBL_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define TIM_DCR_DBL_1 ((uint16_t)0x0200) /*!< Bit 1 */ +#define TIM_DCR_DBL_2 ((uint16_t)0x0400) /*!< Bit 2 */ +#define TIM_DCR_DBL_3 ((uint16_t)0x0800) /*!< Bit 3 */ +#define TIM_DCR_DBL_4 ((uint16_t)0x1000) /*!< Bit 4 */ + +/******************* Bit definition for TIM_DMAR register *******************/ +#define TIM_DMAR_DMAB ((uint16_t)0xFFFF) /*!< DMA register for burst accesses */ + +/******************************************************************************/ +/* */ +/* Real-Time Clock */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for RTC_CRH register ********************/ +#define RTC_CRH_SECIE ((uint8_t)0x01) /*!< Second Interrupt Enable */ +#define RTC_CRH_ALRIE ((uint8_t)0x02) /*!< Alarm Interrupt Enable */ +#define RTC_CRH_OWIE ((uint8_t)0x04) /*!< OverfloW Interrupt Enable */ + +/******************* Bit definition for RTC_CRL register ********************/ +#define RTC_CRL_SECF ((uint8_t)0x01) /*!< Second Flag */ +#define RTC_CRL_ALRF ((uint8_t)0x02) /*!< Alarm Flag */ +#define RTC_CRL_OWF ((uint8_t)0x04) /*!< OverfloW Flag */ +#define RTC_CRL_RSF ((uint8_t)0x08) /*!< Registers Synchronized Flag */ +#define RTC_CRL_CNF ((uint8_t)0x10) /*!< Configuration Flag */ +#define RTC_CRL_RTOFF ((uint8_t)0x20) /*!< RTC operation OFF */ + +/******************* Bit definition for RTC_PRLH register *******************/ +#define RTC_PRLH_PRL ((uint16_t)0x000F) /*!< RTC Prescaler Reload Value High */ + +/******************* Bit definition for RTC_PRLL register *******************/ +#define RTC_PRLL_PRL ((uint16_t)0xFFFF) /*!< RTC Prescaler Reload Value Low */ + +/******************* Bit definition for RTC_DIVH register *******************/ +#define RTC_DIVH_RTC_DIV ((uint16_t)0x000F) /*!< RTC Clock Divider High */ + +/******************* Bit definition for RTC_DIVL register *******************/ +#define RTC_DIVL_RTC_DIV ((uint16_t)0xFFFF) /*!< RTC Clock Divider Low */ + +/******************* Bit definition for RTC_CNTH register *******************/ +#define RTC_CNTH_RTC_CNT ((uint16_t)0xFFFF) /*!< RTC Counter High */ + +/******************* Bit definition for RTC_CNTL register *******************/ +#define RTC_CNTL_RTC_CNT ((uint16_t)0xFFFF) /*!< RTC Counter Low */ + +/******************* Bit definition for RTC_ALRH register *******************/ +#define RTC_ALRH_RTC_ALR ((uint16_t)0xFFFF) /*!< RTC Alarm High */ + +/******************* Bit definition for RTC_ALRL register *******************/ +#define RTC_ALRL_RTC_ALR ((uint16_t)0xFFFF) /*!< RTC Alarm Low */ + +/******************************************************************************/ +/* */ +/* Independent WATCHDOG */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for IWDG_KR register ********************/ +#define IWDG_KR_KEY ((uint16_t)0xFFFF) /*!< Key value (write only, read 0000h) */ + +/******************* Bit definition for IWDG_PR register ********************/ +#define IWDG_PR_PR ((uint8_t)0x07) /*!< PR[2:0] (Prescaler divider) */ +#define IWDG_PR_PR_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define IWDG_PR_PR_1 ((uint8_t)0x02) /*!< Bit 1 */ +#define IWDG_PR_PR_2 ((uint8_t)0x04) /*!< Bit 2 */ + +/******************* Bit definition for IWDG_RLR register *******************/ +#define IWDG_RLR_RL ((uint16_t)0x0FFF) /*!< Watchdog counter reload value */ + +/******************* Bit definition for IWDG_SR register ********************/ +#define IWDG_SR_PVU ((uint8_t)0x01) /*!< Watchdog prescaler value update */ +#define IWDG_SR_RVU ((uint8_t)0x02) /*!< Watchdog counter reload value update */ + +/******************************************************************************/ +/* */ +/* Window WATCHDOG */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for WWDG_CR register ********************/ +#define WWDG_CR_T ((uint8_t)0x7F) /*!< T[6:0] bits (7-Bit counter (MSB to LSB)) */ +#define WWDG_CR_T0 ((uint8_t)0x01) /*!< Bit 0 */ +#define WWDG_CR_T1 ((uint8_t)0x02) /*!< Bit 1 */ +#define WWDG_CR_T2 ((uint8_t)0x04) /*!< Bit 2 */ +#define WWDG_CR_T3 ((uint8_t)0x08) /*!< Bit 3 */ +#define WWDG_CR_T4 ((uint8_t)0x10) /*!< Bit 4 */ +#define WWDG_CR_T5 ((uint8_t)0x20) /*!< Bit 5 */ +#define WWDG_CR_T6 ((uint8_t)0x40) /*!< Bit 6 */ + +#define WWDG_CR_WDGA ((uint8_t)0x80) /*!< Activation bit */ + +/******************* Bit definition for WWDG_CFR register *******************/ +#define WWDG_CFR_W ((uint16_t)0x007F) /*!< W[6:0] bits (7-bit window value) */ +#define WWDG_CFR_W0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define WWDG_CFR_W1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define WWDG_CFR_W2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define WWDG_CFR_W3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define WWDG_CFR_W4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define WWDG_CFR_W5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define WWDG_CFR_W6 ((uint16_t)0x0040) /*!< Bit 6 */ + +#define WWDG_CFR_WDGTB ((uint16_t)0x0180) /*!< WDGTB[1:0] bits (Timer Base) */ +#define WWDG_CFR_WDGTB0 ((uint16_t)0x0080) /*!< Bit 0 */ +#define WWDG_CFR_WDGTB1 ((uint16_t)0x0100) /*!< Bit 1 */ + +#define WWDG_CFR_EWI ((uint16_t)0x0200) /*!< Early Wakeup Interrupt */ + +/******************* Bit definition for WWDG_SR register ********************/ +#define WWDG_SR_EWIF ((uint8_t)0x01) /*!< Early Wakeup Interrupt Flag */ + +/******************************************************************************/ +/* */ +/* Flexible Static Memory Controller */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for FSMC_BCR1 register *******************/ +#define FSMC_BCR1_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR1_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR1_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR1_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR1_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR1_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR1_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR1_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR1_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR1_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR1_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR1_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR1_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR1_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR1_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR1_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR1_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR1_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR2 register *******************/ +#define FSMC_BCR2_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR2_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR2_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR2_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR2_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR2_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR2_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR2_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR2_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR2_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR2_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR2_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR2_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR2_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR2_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR2_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR2_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR2_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR3 register *******************/ +#define FSMC_BCR3_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR3_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR3_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR3_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR3_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR3_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR3_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR3_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR3_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR3_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR3_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit. */ +#define FSMC_BCR3_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR3_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR3_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR3_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR3_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR3_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR3_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BCR4 register *******************/ +#define FSMC_BCR4_MBKEN ((uint32_t)0x00000001) /*!< Memory bank enable bit */ +#define FSMC_BCR4_MUXEN ((uint32_t)0x00000002) /*!< Address/data multiplexing enable bit */ + +#define FSMC_BCR4_MTYP ((uint32_t)0x0000000C) /*!< MTYP[1:0] bits (Memory type) */ +#define FSMC_BCR4_MTYP_0 ((uint32_t)0x00000004) /*!< Bit 0 */ +#define FSMC_BCR4_MTYP_1 ((uint32_t)0x00000008) /*!< Bit 1 */ + +#define FSMC_BCR4_MWID ((uint32_t)0x00000030) /*!< MWID[1:0] bits (Memory data bus width) */ +#define FSMC_BCR4_MWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BCR4_MWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_BCR4_FACCEN ((uint32_t)0x00000040) /*!< Flash access enable */ +#define FSMC_BCR4_BURSTEN ((uint32_t)0x00000100) /*!< Burst enable bit */ +#define FSMC_BCR4_WAITPOL ((uint32_t)0x00000200) /*!< Wait signal polarity bit */ +#define FSMC_BCR4_WRAPMOD ((uint32_t)0x00000400) /*!< Wrapped burst mode support */ +#define FSMC_BCR4_WAITCFG ((uint32_t)0x00000800) /*!< Wait timing configuration */ +#define FSMC_BCR4_WREN ((uint32_t)0x00001000) /*!< Write enable bit */ +#define FSMC_BCR4_WAITEN ((uint32_t)0x00002000) /*!< Wait enable bit */ +#define FSMC_BCR4_EXTMOD ((uint32_t)0x00004000) /*!< Extended mode enable */ +#define FSMC_BCR4_ASYNCWAIT ((uint32_t)0x00008000) /*!< Asynchronous wait */ +#define FSMC_BCR4_CBURSTRW ((uint32_t)0x00080000) /*!< Write burst enable */ + +/****************** Bit definition for FSMC_BTR1 register ******************/ +#define FSMC_BTR1_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR1_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR1_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR1_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR1_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR1_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR1_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR1_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR1_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR1_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR1_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR1_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR1_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR1_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR1_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR1_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR1_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR1_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR1_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR1_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR1_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR1_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR1_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR1_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR1_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR1_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR1_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR1_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR1_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR1_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR1_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR1_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR1_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BTR2 register *******************/ +#define FSMC_BTR2_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR2_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR2_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR2_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR2_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR2_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR2_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR2_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR2_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR2_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR2_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR2_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR2_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR2_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR2_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR2_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR2_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR2_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR2_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR2_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR2_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR2_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR2_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR2_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR2_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR2_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR2_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR2_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR2_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR2_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR2_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR2_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR2_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/******************* Bit definition for FSMC_BTR3 register *******************/ +#define FSMC_BTR3_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR3_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR3_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR3_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR3_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR3_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR3_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR3_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR3_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR3_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR3_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR3_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR3_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR3_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR3_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR3_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR3_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR3_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR3_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR3_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR3_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR3_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR3_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR3_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR3_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR3_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR3_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR3_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR3_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR3_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR3_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR3_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR3_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BTR4 register *******************/ +#define FSMC_BTR4_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BTR4_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BTR4_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BTR4_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BTR4_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BTR4_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BTR4_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BTR4_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BTR4_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BTR4_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BTR4_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BTR4_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BTR4_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BTR4_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BTR4_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BTR4_BUSTURN ((uint32_t)0x000F0000) /*!< BUSTURN[3:0] bits (Bus turnaround phase duration) */ +#define FSMC_BTR4_BUSTURN_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_BTR4_BUSTURN_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_BTR4_BUSTURN_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_BTR4_BUSTURN_3 ((uint32_t)0x00080000) /*!< Bit 3 */ + +#define FSMC_BTR4_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BTR4_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BTR4_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BTR4_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BTR4_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BTR4_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BTR4_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BTR4_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BTR4_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BTR4_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BTR4_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BTR4_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BTR4_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR1 register ******************/ +#define FSMC_BWTR1_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR1_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR1_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR1_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR1_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR1_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR1_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR1_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR1_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR1_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR1_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR1_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR1_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR1_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR1_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR1_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR1_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR1_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR1_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR1_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR1_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR1_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR1_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR1_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR1_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR1_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR1_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR1_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR2 register ******************/ +#define FSMC_BWTR2_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR2_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR2_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR2_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR2_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR2_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR2_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR2_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR2_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR2_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR2_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR2_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR2_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR2_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR2_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR2_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR2_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR2_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1*/ +#define FSMC_BWTR2_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR2_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR2_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR2_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR2_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR2_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR2_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR2_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR2_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR2_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR3 register ******************/ +#define FSMC_BWTR3_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR3_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR3_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR3_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR3_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR3_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR3_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR3_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR3_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR3_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR3_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR3_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR3_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR3_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR3_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR3_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR3_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR3_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR3_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR3_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR3_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR3_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR3_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR3_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR3_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR3_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR3_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR3_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_BWTR4 register ******************/ +#define FSMC_BWTR4_ADDSET ((uint32_t)0x0000000F) /*!< ADDSET[3:0] bits (Address setup phase duration) */ +#define FSMC_BWTR4_ADDSET_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_BWTR4_ADDSET_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_BWTR4_ADDSET_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_BWTR4_ADDSET_3 ((uint32_t)0x00000008) /*!< Bit 3 */ + +#define FSMC_BWTR4_ADDHLD ((uint32_t)0x000000F0) /*!< ADDHLD[3:0] bits (Address-hold phase duration) */ +#define FSMC_BWTR4_ADDHLD_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_BWTR4_ADDHLD_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define FSMC_BWTR4_ADDHLD_2 ((uint32_t)0x00000040) /*!< Bit 2 */ +#define FSMC_BWTR4_ADDHLD_3 ((uint32_t)0x00000080) /*!< Bit 3 */ + +#define FSMC_BWTR4_DATAST ((uint32_t)0x0000FF00) /*!< DATAST [3:0] bits (Data-phase duration) */ +#define FSMC_BWTR4_DATAST_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_BWTR4_DATAST_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_BWTR4_DATAST_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_BWTR4_DATAST_3 ((uint32_t)0x00000800) /*!< Bit 3 */ + +#define FSMC_BWTR4_CLKDIV ((uint32_t)0x00F00000) /*!< CLKDIV[3:0] bits (Clock divide ratio) */ +#define FSMC_BWTR4_CLKDIV_0 ((uint32_t)0x00100000) /*!< Bit 0 */ +#define FSMC_BWTR4_CLKDIV_1 ((uint32_t)0x00200000) /*!< Bit 1 */ +#define FSMC_BWTR4_CLKDIV_2 ((uint32_t)0x00400000) /*!< Bit 2 */ +#define FSMC_BWTR4_CLKDIV_3 ((uint32_t)0x00800000) /*!< Bit 3 */ + +#define FSMC_BWTR4_DATLAT ((uint32_t)0x0F000000) /*!< DATLA[3:0] bits (Data latency) */ +#define FSMC_BWTR4_DATLAT_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_BWTR4_DATLAT_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_BWTR4_DATLAT_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_BWTR4_DATLAT_3 ((uint32_t)0x08000000) /*!< Bit 3 */ + +#define FSMC_BWTR4_ACCMOD ((uint32_t)0x30000000) /*!< ACCMOD[1:0] bits (Access mode) */ +#define FSMC_BWTR4_ACCMOD_0 ((uint32_t)0x10000000) /*!< Bit 0 */ +#define FSMC_BWTR4_ACCMOD_1 ((uint32_t)0x20000000) /*!< Bit 1 */ + +/****************** Bit definition for FSMC_PCR2 register *******************/ +#define FSMC_PCR2_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR2_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR2_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR2_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR2_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR2_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR2_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR2_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR2_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR2_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR2_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR2_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR2_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR2_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR2_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR2_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR2_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR2_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[1:0] bits (ECC page size) */ +#define FSMC_PCR2_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR2_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR2_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/****************** Bit definition for FSMC_PCR3 register *******************/ +#define FSMC_PCR3_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR3_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR3_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR3_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR3_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR3_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR3_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR3_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR3_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR3_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR3_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR3_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR3_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR3_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR3_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR3_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR3_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR3_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[2:0] bits (ECC page size) */ +#define FSMC_PCR3_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR3_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR3_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/****************** Bit definition for FSMC_PCR4 register *******************/ +#define FSMC_PCR4_PWAITEN ((uint32_t)0x00000002) /*!< Wait feature enable bit */ +#define FSMC_PCR4_PBKEN ((uint32_t)0x00000004) /*!< PC Card/NAND Flash memory bank enable bit */ +#define FSMC_PCR4_PTYP ((uint32_t)0x00000008) /*!< Memory type */ + +#define FSMC_PCR4_PWID ((uint32_t)0x00000030) /*!< PWID[1:0] bits (NAND Flash databus width) */ +#define FSMC_PCR4_PWID_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define FSMC_PCR4_PWID_1 ((uint32_t)0x00000020) /*!< Bit 1 */ + +#define FSMC_PCR4_ECCEN ((uint32_t)0x00000040) /*!< ECC computation logic enable bit */ + +#define FSMC_PCR4_TCLR ((uint32_t)0x00001E00) /*!< TCLR[3:0] bits (CLE to RE delay) */ +#define FSMC_PCR4_TCLR_0 ((uint32_t)0x00000200) /*!< Bit 0 */ +#define FSMC_PCR4_TCLR_1 ((uint32_t)0x00000400) /*!< Bit 1 */ +#define FSMC_PCR4_TCLR_2 ((uint32_t)0x00000800) /*!< Bit 2 */ +#define FSMC_PCR4_TCLR_3 ((uint32_t)0x00001000) /*!< Bit 3 */ + +#define FSMC_PCR4_TAR ((uint32_t)0x0001E000) /*!< TAR[3:0] bits (ALE to RE delay) */ +#define FSMC_PCR4_TAR_0 ((uint32_t)0x00002000) /*!< Bit 0 */ +#define FSMC_PCR4_TAR_1 ((uint32_t)0x00004000) /*!< Bit 1 */ +#define FSMC_PCR4_TAR_2 ((uint32_t)0x00008000) /*!< Bit 2 */ +#define FSMC_PCR4_TAR_3 ((uint32_t)0x00010000) /*!< Bit 3 */ + +#define FSMC_PCR4_ECCPS ((uint32_t)0x000E0000) /*!< ECCPS[2:0] bits (ECC page size) */ +#define FSMC_PCR4_ECCPS_0 ((uint32_t)0x00020000) /*!< Bit 0 */ +#define FSMC_PCR4_ECCPS_1 ((uint32_t)0x00040000) /*!< Bit 1 */ +#define FSMC_PCR4_ECCPS_2 ((uint32_t)0x00080000) /*!< Bit 2 */ + +/******************* Bit definition for FSMC_SR2 register *******************/ +#define FSMC_SR2_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR2_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR2_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR2_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR2_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR2_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR2_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/******************* Bit definition for FSMC_SR3 register *******************/ +#define FSMC_SR3_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR3_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR3_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR3_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR3_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR3_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR3_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/******************* Bit definition for FSMC_SR4 register *******************/ +#define FSMC_SR4_IRS ((uint8_t)0x01) /*!< Interrupt Rising Edge status */ +#define FSMC_SR4_ILS ((uint8_t)0x02) /*!< Interrupt Level status */ +#define FSMC_SR4_IFS ((uint8_t)0x04) /*!< Interrupt Falling Edge status */ +#define FSMC_SR4_IREN ((uint8_t)0x08) /*!< Interrupt Rising Edge detection Enable bit */ +#define FSMC_SR4_ILEN ((uint8_t)0x10) /*!< Interrupt Level detection Enable bit */ +#define FSMC_SR4_IFEN ((uint8_t)0x20) /*!< Interrupt Falling Edge detection Enable bit */ +#define FSMC_SR4_FEMPT ((uint8_t)0x40) /*!< FIFO empty */ + +/****************** Bit definition for FSMC_PMEM2 register ******************/ +#define FSMC_PMEM2_MEMSET2 ((uint32_t)0x000000FF) /*!< MEMSET2[7:0] bits (Common memory 2 setup time) */ +#define FSMC_PMEM2_MEMSET2_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMSET2_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMSET2_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMSET2_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMSET2_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMSET2_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMSET2_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMSET2_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMWAIT2 ((uint32_t)0x0000FF00) /*!< MEMWAIT2[7:0] bits (Common memory 2 wait time) */ +#define FSMC_PMEM2_MEMWAIT2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMWAIT2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMWAIT2_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMWAIT2_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMWAIT2_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMWAIT2_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMWAIT2_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMWAIT2_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMHOLD2 ((uint32_t)0x00FF0000) /*!< MEMHOLD2[7:0] bits (Common memory 2 hold time) */ +#define FSMC_PMEM2_MEMHOLD2_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMHOLD2_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMHOLD2_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMHOLD2_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMHOLD2_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMHOLD2_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMHOLD2_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMHOLD2_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM2_MEMHIZ2 ((uint32_t)0xFF000000) /*!< MEMHIZ2[7:0] bits (Common memory 2 databus HiZ time) */ +#define FSMC_PMEM2_MEMHIZ2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM2_MEMHIZ2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM2_MEMHIZ2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM2_MEMHIZ2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM2_MEMHIZ2_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM2_MEMHIZ2_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM2_MEMHIZ2_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM2_MEMHIZ2_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PMEM3 register ******************/ +#define FSMC_PMEM3_MEMSET3 ((uint32_t)0x000000FF) /*!< MEMSET3[7:0] bits (Common memory 3 setup time) */ +#define FSMC_PMEM3_MEMSET3_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMSET3_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMSET3_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMSET3_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMSET3_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMSET3_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMSET3_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMSET3_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMWAIT3 ((uint32_t)0x0000FF00) /*!< MEMWAIT3[7:0] bits (Common memory 3 wait time) */ +#define FSMC_PMEM3_MEMWAIT3_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMWAIT3_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMWAIT3_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMWAIT3_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMWAIT3_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMWAIT3_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMWAIT3_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMWAIT3_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMHOLD3 ((uint32_t)0x00FF0000) /*!< MEMHOLD3[7:0] bits (Common memory 3 hold time) */ +#define FSMC_PMEM3_MEMHOLD3_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMHOLD3_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMHOLD3_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMHOLD3_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMHOLD3_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMHOLD3_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMHOLD3_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMHOLD3_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM3_MEMHIZ3 ((uint32_t)0xFF000000) /*!< MEMHIZ3[7:0] bits (Common memory 3 databus HiZ time) */ +#define FSMC_PMEM3_MEMHIZ3_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM3_MEMHIZ3_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM3_MEMHIZ3_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM3_MEMHIZ3_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM3_MEMHIZ3_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM3_MEMHIZ3_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM3_MEMHIZ3_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM3_MEMHIZ3_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PMEM4 register ******************/ +#define FSMC_PMEM4_MEMSET4 ((uint32_t)0x000000FF) /*!< MEMSET4[7:0] bits (Common memory 4 setup time) */ +#define FSMC_PMEM4_MEMSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMWAIT4 ((uint32_t)0x0000FF00) /*!< MEMWAIT4[7:0] bits (Common memory 4 wait time) */ +#define FSMC_PMEM4_MEMWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMHOLD4 ((uint32_t)0x00FF0000) /*!< MEMHOLD4[7:0] bits (Common memory 4 hold time) */ +#define FSMC_PMEM4_MEMHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PMEM4_MEMHIZ4 ((uint32_t)0xFF000000) /*!< MEMHIZ4[7:0] bits (Common memory 4 databus HiZ time) */ +#define FSMC_PMEM4_MEMHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PMEM4_MEMHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PMEM4_MEMHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PMEM4_MEMHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PMEM4_MEMHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PMEM4_MEMHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PMEM4_MEMHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PMEM4_MEMHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT2 register ******************/ +#define FSMC_PATT2_ATTSET2 ((uint32_t)0x000000FF) /*!< ATTSET2[7:0] bits (Attribute memory 2 setup time) */ +#define FSMC_PATT2_ATTSET2_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT2_ATTSET2_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT2_ATTSET2_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT2_ATTSET2_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT2_ATTSET2_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT2_ATTSET2_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT2_ATTSET2_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT2_ATTSET2_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTWAIT2 ((uint32_t)0x0000FF00) /*!< ATTWAIT2[7:0] bits (Attribute memory 2 wait time) */ +#define FSMC_PATT2_ATTWAIT2_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT2_ATTWAIT2_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT2_ATTWAIT2_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT2_ATTWAIT2_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT2_ATTWAIT2_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTWAIT2_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTWAIT2_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTWAIT2_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTHOLD2 ((uint32_t)0x00FF0000) /*!< ATTHOLD2[7:0] bits (Attribute memory 2 hold time) */ +#define FSMC_PATT2_ATTHOLD2_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT2_ATTHOLD2_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT2_ATTHOLD2_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT2_ATTHOLD2_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT2_ATTHOLD2_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTHOLD2_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTHOLD2_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTHOLD2_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT2_ATTHIZ2 ((uint32_t)0xFF000000) /*!< ATTHIZ2[7:0] bits (Attribute memory 2 databus HiZ time) */ +#define FSMC_PATT2_ATTHIZ2_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT2_ATTHIZ2_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT2_ATTHIZ2_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT2_ATTHIZ2_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT2_ATTHIZ2_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT2_ATTHIZ2_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT2_ATTHIZ2_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT2_ATTHIZ2_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT3 register ******************/ +#define FSMC_PATT3_ATTSET3 ((uint32_t)0x000000FF) /*!< ATTSET3[7:0] bits (Attribute memory 3 setup time) */ +#define FSMC_PATT3_ATTSET3_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT3_ATTSET3_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT3_ATTSET3_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT3_ATTSET3_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT3_ATTSET3_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT3_ATTSET3_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT3_ATTSET3_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT3_ATTSET3_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTWAIT3 ((uint32_t)0x0000FF00) /*!< ATTWAIT3[7:0] bits (Attribute memory 3 wait time) */ +#define FSMC_PATT3_ATTWAIT3_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT3_ATTWAIT3_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT3_ATTWAIT3_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT3_ATTWAIT3_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT3_ATTWAIT3_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTWAIT3_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTWAIT3_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTWAIT3_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTHOLD3 ((uint32_t)0x00FF0000) /*!< ATTHOLD3[7:0] bits (Attribute memory 3 hold time) */ +#define FSMC_PATT3_ATTHOLD3_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT3_ATTHOLD3_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT3_ATTHOLD3_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT3_ATTHOLD3_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT3_ATTHOLD3_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTHOLD3_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTHOLD3_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTHOLD3_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT3_ATTHIZ3 ((uint32_t)0xFF000000) /*!< ATTHIZ3[7:0] bits (Attribute memory 3 databus HiZ time) */ +#define FSMC_PATT3_ATTHIZ3_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT3_ATTHIZ3_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT3_ATTHIZ3_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT3_ATTHIZ3_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT3_ATTHIZ3_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT3_ATTHIZ3_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT3_ATTHIZ3_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT3_ATTHIZ3_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PATT4 register ******************/ +#define FSMC_PATT4_ATTSET4 ((uint32_t)0x000000FF) /*!< ATTSET4[7:0] bits (Attribute memory 4 setup time) */ +#define FSMC_PATT4_ATTSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PATT4_ATTSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PATT4_ATTSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PATT4_ATTSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PATT4_ATTSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PATT4_ATTSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PATT4_ATTSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PATT4_ATTSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTWAIT4 ((uint32_t)0x0000FF00) /*!< ATTWAIT4[7:0] bits (Attribute memory 4 wait time) */ +#define FSMC_PATT4_ATTWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PATT4_ATTWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PATT4_ATTWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PATT4_ATTWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PATT4_ATTWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTHOLD4 ((uint32_t)0x00FF0000) /*!< ATTHOLD4[7:0] bits (Attribute memory 4 hold time) */ +#define FSMC_PATT4_ATTHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PATT4_ATTHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PATT4_ATTHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PATT4_ATTHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PATT4_ATTHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PATT4_ATTHIZ4 ((uint32_t)0xFF000000) /*!< ATTHIZ4[7:0] bits (Attribute memory 4 databus HiZ time) */ +#define FSMC_PATT4_ATTHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PATT4_ATTHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PATT4_ATTHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PATT4_ATTHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PATT4_ATTHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PATT4_ATTHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PATT4_ATTHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PATT4_ATTHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_PIO4 register *******************/ +#define FSMC_PIO4_IOSET4 ((uint32_t)0x000000FF) /*!< IOSET4[7:0] bits (I/O 4 setup time) */ +#define FSMC_PIO4_IOSET4_0 ((uint32_t)0x00000001) /*!< Bit 0 */ +#define FSMC_PIO4_IOSET4_1 ((uint32_t)0x00000002) /*!< Bit 1 */ +#define FSMC_PIO4_IOSET4_2 ((uint32_t)0x00000004) /*!< Bit 2 */ +#define FSMC_PIO4_IOSET4_3 ((uint32_t)0x00000008) /*!< Bit 3 */ +#define FSMC_PIO4_IOSET4_4 ((uint32_t)0x00000010) /*!< Bit 4 */ +#define FSMC_PIO4_IOSET4_5 ((uint32_t)0x00000020) /*!< Bit 5 */ +#define FSMC_PIO4_IOSET4_6 ((uint32_t)0x00000040) /*!< Bit 6 */ +#define FSMC_PIO4_IOSET4_7 ((uint32_t)0x00000080) /*!< Bit 7 */ + +#define FSMC_PIO4_IOWAIT4 ((uint32_t)0x0000FF00) /*!< IOWAIT4[7:0] bits (I/O 4 wait time) */ +#define FSMC_PIO4_IOWAIT4_0 ((uint32_t)0x00000100) /*!< Bit 0 */ +#define FSMC_PIO4_IOWAIT4_1 ((uint32_t)0x00000200) /*!< Bit 1 */ +#define FSMC_PIO4_IOWAIT4_2 ((uint32_t)0x00000400) /*!< Bit 2 */ +#define FSMC_PIO4_IOWAIT4_3 ((uint32_t)0x00000800) /*!< Bit 3 */ +#define FSMC_PIO4_IOWAIT4_4 ((uint32_t)0x00001000) /*!< Bit 4 */ +#define FSMC_PIO4_IOWAIT4_5 ((uint32_t)0x00002000) /*!< Bit 5 */ +#define FSMC_PIO4_IOWAIT4_6 ((uint32_t)0x00004000) /*!< Bit 6 */ +#define FSMC_PIO4_IOWAIT4_7 ((uint32_t)0x00008000) /*!< Bit 7 */ + +#define FSMC_PIO4_IOHOLD4 ((uint32_t)0x00FF0000) /*!< IOHOLD4[7:0] bits (I/O 4 hold time) */ +#define FSMC_PIO4_IOHOLD4_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define FSMC_PIO4_IOHOLD4_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define FSMC_PIO4_IOHOLD4_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define FSMC_PIO4_IOHOLD4_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define FSMC_PIO4_IOHOLD4_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define FSMC_PIO4_IOHOLD4_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define FSMC_PIO4_IOHOLD4_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define FSMC_PIO4_IOHOLD4_7 ((uint32_t)0x00800000) /*!< Bit 7 */ + +#define FSMC_PIO4_IOHIZ4 ((uint32_t)0xFF000000) /*!< IOHIZ4[7:0] bits (I/O 4 databus HiZ time) */ +#define FSMC_PIO4_IOHIZ4_0 ((uint32_t)0x01000000) /*!< Bit 0 */ +#define FSMC_PIO4_IOHIZ4_1 ((uint32_t)0x02000000) /*!< Bit 1 */ +#define FSMC_PIO4_IOHIZ4_2 ((uint32_t)0x04000000) /*!< Bit 2 */ +#define FSMC_PIO4_IOHIZ4_3 ((uint32_t)0x08000000) /*!< Bit 3 */ +#define FSMC_PIO4_IOHIZ4_4 ((uint32_t)0x10000000) /*!< Bit 4 */ +#define FSMC_PIO4_IOHIZ4_5 ((uint32_t)0x20000000) /*!< Bit 5 */ +#define FSMC_PIO4_IOHIZ4_6 ((uint32_t)0x40000000) /*!< Bit 6 */ +#define FSMC_PIO4_IOHIZ4_7 ((uint32_t)0x80000000) /*!< Bit 7 */ + +/****************** Bit definition for FSMC_ECCR2 register ******************/ +#define FSMC_ECCR2_ECC2 ((uint32_t)0xFFFFFFFF) /*!< ECC result */ + +/****************** Bit definition for FSMC_ECCR3 register ******************/ +#define FSMC_ECCR3_ECC3 ((uint32_t)0xFFFFFFFF) /*!< ECC result */ + +/******************************************************************************/ +/* */ +/* SD host Interface */ +/* */ +/******************************************************************************/ + +/****************** Bit definition for SDIO_POWER register ******************/ +#define SDIO_POWER_PWRCTRL ((uint8_t)0x03) /*!< PWRCTRL[1:0] bits (Power supply control bits) */ +#define SDIO_POWER_PWRCTRL_0 ((uint8_t)0x01) /*!< Bit 0 */ +#define SDIO_POWER_PWRCTRL_1 ((uint8_t)0x02) /*!< Bit 1 */ + +/****************** Bit definition for SDIO_CLKCR register ******************/ +#define SDIO_CLKCR_CLKDIV ((uint16_t)0x00FF) /*!< Clock divide factor */ +#define SDIO_CLKCR_CLKEN ((uint16_t)0x0100) /*!< Clock enable bit */ +#define SDIO_CLKCR_PWRSAV ((uint16_t)0x0200) /*!< Power saving configuration bit */ +#define SDIO_CLKCR_BYPASS ((uint16_t)0x0400) /*!< Clock divider bypass enable bit */ + +#define SDIO_CLKCR_WIDBUS ((uint16_t)0x1800) /*!< WIDBUS[1:0] bits (Wide bus mode enable bit) */ +#define SDIO_CLKCR_WIDBUS_0 ((uint16_t)0x0800) /*!< Bit 0 */ +#define SDIO_CLKCR_WIDBUS_1 ((uint16_t)0x1000) /*!< Bit 1 */ + +#define SDIO_CLKCR_NEGEDGE ((uint16_t)0x2000) /*!< SDIO_CK dephasing selection bit */ +#define SDIO_CLKCR_HWFC_EN ((uint16_t)0x4000) /*!< HW Flow Control enable */ + +/******************* Bit definition for SDIO_ARG register *******************/ +#define SDIO_ARG_CMDARG ((uint32_t)0xFFFFFFFF) /*!< Command argument */ + +/******************* Bit definition for SDIO_CMD register *******************/ +#define SDIO_CMD_CMDINDEX ((uint16_t)0x003F) /*!< Command Index */ + +#define SDIO_CMD_WAITRESP ((uint16_t)0x00C0) /*!< WAITRESP[1:0] bits (Wait for response bits) */ +#define SDIO_CMD_WAITRESP_0 ((uint16_t)0x0040) /*!< Bit 0 */ +#define SDIO_CMD_WAITRESP_1 ((uint16_t)0x0080) /*!< Bit 1 */ + +#define SDIO_CMD_WAITINT ((uint16_t)0x0100) /*!< CPSM Waits for Interrupt Request */ +#define SDIO_CMD_WAITPEND ((uint16_t)0x0200) /*!< CPSM Waits for ends of data transfer (CmdPend internal signal) */ +#define SDIO_CMD_CPSMEN ((uint16_t)0x0400) /*!< Command path state machine (CPSM) Enable bit */ +#define SDIO_CMD_SDIOSUSPEND ((uint16_t)0x0800) /*!< SD I/O suspend command */ +#define SDIO_CMD_ENCMDCOMPL ((uint16_t)0x1000) /*!< Enable CMD completion */ +#define SDIO_CMD_NIEN ((uint16_t)0x2000) /*!< Not Interrupt Enable */ +#define SDIO_CMD_CEATACMD ((uint16_t)0x4000) /*!< CE-ATA command */ + +/***************** Bit definition for SDIO_RESPCMD register *****************/ +#define SDIO_RESPCMD_RESPCMD ((uint8_t)0x3F) /*!< Response command index */ + +/****************** Bit definition for SDIO_RESP0 register ******************/ +#define SDIO_RESP0_CARDSTATUS0 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP1 register ******************/ +#define SDIO_RESP1_CARDSTATUS1 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP2 register ******************/ +#define SDIO_RESP2_CARDSTATUS2 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP3 register ******************/ +#define SDIO_RESP3_CARDSTATUS3 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_RESP4 register ******************/ +#define SDIO_RESP4_CARDSTATUS4 ((uint32_t)0xFFFFFFFF) /*!< Card Status */ + +/****************** Bit definition for SDIO_DTIMER register *****************/ +#define SDIO_DTIMER_DATATIME ((uint32_t)0xFFFFFFFF) /*!< Data timeout period. */ + +/****************** Bit definition for SDIO_DLEN register *******************/ +#define SDIO_DLEN_DATALENGTH ((uint32_t)0x01FFFFFF) /*!< Data length value */ + +/****************** Bit definition for SDIO_DCTRL register ******************/ +#define SDIO_DCTRL_DTEN ((uint16_t)0x0001) /*!< Data transfer enabled bit */ +#define SDIO_DCTRL_DTDIR ((uint16_t)0x0002) /*!< Data transfer direction selection */ +#define SDIO_DCTRL_DTMODE ((uint16_t)0x0004) /*!< Data transfer mode selection */ +#define SDIO_DCTRL_DMAEN ((uint16_t)0x0008) /*!< DMA enabled bit */ + +#define SDIO_DCTRL_DBLOCKSIZE ((uint16_t)0x00F0) /*!< DBLOCKSIZE[3:0] bits (Data block size) */ +#define SDIO_DCTRL_DBLOCKSIZE_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define SDIO_DCTRL_DBLOCKSIZE_1 ((uint16_t)0x0020) /*!< Bit 1 */ +#define SDIO_DCTRL_DBLOCKSIZE_2 ((uint16_t)0x0040) /*!< Bit 2 */ +#define SDIO_DCTRL_DBLOCKSIZE_3 ((uint16_t)0x0080) /*!< Bit 3 */ + +#define SDIO_DCTRL_RWSTART ((uint16_t)0x0100) /*!< Read wait start */ +#define SDIO_DCTRL_RWSTOP ((uint16_t)0x0200) /*!< Read wait stop */ +#define SDIO_DCTRL_RWMOD ((uint16_t)0x0400) /*!< Read wait mode */ +#define SDIO_DCTRL_SDIOEN ((uint16_t)0x0800) /*!< SD I/O enable functions */ + +/****************** Bit definition for SDIO_DCOUNT register *****************/ +#define SDIO_DCOUNT_DATACOUNT ((uint32_t)0x01FFFFFF) /*!< Data count value */ + +/****************** Bit definition for SDIO_STA register ********************/ +#define SDIO_STA_CCRCFAIL ((uint32_t)0x00000001) /*!< Command response received (CRC check failed) */ +#define SDIO_STA_DCRCFAIL ((uint32_t)0x00000002) /*!< Data block sent/received (CRC check failed) */ +#define SDIO_STA_CTIMEOUT ((uint32_t)0x00000004) /*!< Command response timeout */ +#define SDIO_STA_DTIMEOUT ((uint32_t)0x00000008) /*!< Data timeout */ +#define SDIO_STA_TXUNDERR ((uint32_t)0x00000010) /*!< Transmit FIFO underrun error */ +#define SDIO_STA_RXOVERR ((uint32_t)0x00000020) /*!< Received FIFO overrun error */ +#define SDIO_STA_CMDREND ((uint32_t)0x00000040) /*!< Command response received (CRC check passed) */ +#define SDIO_STA_CMDSENT ((uint32_t)0x00000080) /*!< Command sent (no response required) */ +#define SDIO_STA_DATAEND ((uint32_t)0x00000100) /*!< Data end (data counter, SDIDCOUNT, is zero) */ +#define SDIO_STA_STBITERR ((uint32_t)0x00000200) /*!< Start bit not detected on all data signals in wide bus mode */ +#define SDIO_STA_DBCKEND ((uint32_t)0x00000400) /*!< Data block sent/received (CRC check passed) */ +#define SDIO_STA_CMDACT ((uint32_t)0x00000800) /*!< Command transfer in progress */ +#define SDIO_STA_TXACT ((uint32_t)0x00001000) /*!< Data transmit in progress */ +#define SDIO_STA_RXACT ((uint32_t)0x00002000) /*!< Data receive in progress */ +#define SDIO_STA_TXFIFOHE ((uint32_t)0x00004000) /*!< Transmit FIFO Half Empty: at least 8 words can be written into the FIFO */ +#define SDIO_STA_RXFIFOHF ((uint32_t)0x00008000) /*!< Receive FIFO Half Full: there are at least 8 words in the FIFO */ +#define SDIO_STA_TXFIFOF ((uint32_t)0x00010000) /*!< Transmit FIFO full */ +#define SDIO_STA_RXFIFOF ((uint32_t)0x00020000) /*!< Receive FIFO full */ +#define SDIO_STA_TXFIFOE ((uint32_t)0x00040000) /*!< Transmit FIFO empty */ +#define SDIO_STA_RXFIFOE ((uint32_t)0x00080000) /*!< Receive FIFO empty */ +#define SDIO_STA_TXDAVL ((uint32_t)0x00100000) /*!< Data available in transmit FIFO */ +#define SDIO_STA_RXDAVL ((uint32_t)0x00200000) /*!< Data available in receive FIFO */ +#define SDIO_STA_SDIOIT ((uint32_t)0x00400000) /*!< SDIO interrupt received */ +#define SDIO_STA_CEATAEND ((uint32_t)0x00800000) /*!< CE-ATA command completion signal received for CMD61 */ + +/******************* Bit definition for SDIO_ICR register *******************/ +#define SDIO_ICR_CCRCFAILC ((uint32_t)0x00000001) /*!< CCRCFAIL flag clear bit */ +#define SDIO_ICR_DCRCFAILC ((uint32_t)0x00000002) /*!< DCRCFAIL flag clear bit */ +#define SDIO_ICR_CTIMEOUTC ((uint32_t)0x00000004) /*!< CTIMEOUT flag clear bit */ +#define SDIO_ICR_DTIMEOUTC ((uint32_t)0x00000008) /*!< DTIMEOUT flag clear bit */ +#define SDIO_ICR_TXUNDERRC ((uint32_t)0x00000010) /*!< TXUNDERR flag clear bit */ +#define SDIO_ICR_RXOVERRC ((uint32_t)0x00000020) /*!< RXOVERR flag clear bit */ +#define SDIO_ICR_CMDRENDC ((uint32_t)0x00000040) /*!< CMDREND flag clear bit */ +#define SDIO_ICR_CMDSENTC ((uint32_t)0x00000080) /*!< CMDSENT flag clear bit */ +#define SDIO_ICR_DATAENDC ((uint32_t)0x00000100) /*!< DATAEND flag clear bit */ +#define SDIO_ICR_STBITERRC ((uint32_t)0x00000200) /*!< STBITERR flag clear bit */ +#define SDIO_ICR_DBCKENDC ((uint32_t)0x00000400) /*!< DBCKEND flag clear bit */ +#define SDIO_ICR_SDIOITC ((uint32_t)0x00400000) /*!< SDIOIT flag clear bit */ +#define SDIO_ICR_CEATAENDC ((uint32_t)0x00800000) /*!< CEATAEND flag clear bit */ + +/****************** Bit definition for SDIO_MASK register *******************/ +#define SDIO_MASK_CCRCFAILIE ((uint32_t)0x00000001) /*!< Command CRC Fail Interrupt Enable */ +#define SDIO_MASK_DCRCFAILIE ((uint32_t)0x00000002) /*!< Data CRC Fail Interrupt Enable */ +#define SDIO_MASK_CTIMEOUTIE ((uint32_t)0x00000004) /*!< Command TimeOut Interrupt Enable */ +#define SDIO_MASK_DTIMEOUTIE ((uint32_t)0x00000008) /*!< Data TimeOut Interrupt Enable */ +#define SDIO_MASK_TXUNDERRIE ((uint32_t)0x00000010) /*!< Tx FIFO UnderRun Error Interrupt Enable */ +#define SDIO_MASK_RXOVERRIE ((uint32_t)0x00000020) /*!< Rx FIFO OverRun Error Interrupt Enable */ +#define SDIO_MASK_CMDRENDIE ((uint32_t)0x00000040) /*!< Command Response Received Interrupt Enable */ +#define SDIO_MASK_CMDSENTIE ((uint32_t)0x00000080) /*!< Command Sent Interrupt Enable */ +#define SDIO_MASK_DATAENDIE ((uint32_t)0x00000100) /*!< Data End Interrupt Enable */ +#define SDIO_MASK_STBITERRIE ((uint32_t)0x00000200) /*!< Start Bit Error Interrupt Enable */ +#define SDIO_MASK_DBCKENDIE ((uint32_t)0x00000400) /*!< Data Block End Interrupt Enable */ +#define SDIO_MASK_CMDACTIE ((uint32_t)0x00000800) /*!< Command Acting Interrupt Enable */ +#define SDIO_MASK_TXACTIE ((uint32_t)0x00001000) /*!< Data Transmit Acting Interrupt Enable */ +#define SDIO_MASK_RXACTIE ((uint32_t)0x00002000) /*!< Data receive acting interrupt enabled */ +#define SDIO_MASK_TXFIFOHEIE ((uint32_t)0x00004000) /*!< Tx FIFO Half Empty interrupt Enable */ +#define SDIO_MASK_RXFIFOHFIE ((uint32_t)0x00008000) /*!< Rx FIFO Half Full interrupt Enable */ +#define SDIO_MASK_TXFIFOFIE ((uint32_t)0x00010000) /*!< Tx FIFO Full interrupt Enable */ +#define SDIO_MASK_RXFIFOFIE ((uint32_t)0x00020000) /*!< Rx FIFO Full interrupt Enable */ +#define SDIO_MASK_TXFIFOEIE ((uint32_t)0x00040000) /*!< Tx FIFO Empty interrupt Enable */ +#define SDIO_MASK_RXFIFOEIE ((uint32_t)0x00080000) /*!< Rx FIFO Empty interrupt Enable */ +#define SDIO_MASK_TXDAVLIE ((uint32_t)0x00100000) /*!< Data available in Tx FIFO interrupt Enable */ +#define SDIO_MASK_RXDAVLIE ((uint32_t)0x00200000) /*!< Data available in Rx FIFO interrupt Enable */ +#define SDIO_MASK_SDIOITIE ((uint32_t)0x00400000) /*!< SDIO Mode Interrupt Received interrupt Enable */ +#define SDIO_MASK_CEATAENDIE ((uint32_t)0x00800000) /*!< CE-ATA command completion signal received Interrupt Enable */ + +/***************** Bit definition for SDIO_FIFOCNT register *****************/ +#define SDIO_FIFOCNT_FIFOCOUNT ((uint32_t)0x00FFFFFF) /*!< Remaining number of words to be written to or read from the FIFO */ + +/****************** Bit definition for SDIO_FIFO register *******************/ +#define SDIO_FIFO_FIFODATA ((uint32_t)0xFFFFFFFF) /*!< Receive and transmit FIFO data */ + +/******************************************************************************/ +/* */ +/* USB Device FS */ +/* */ +/******************************************************************************/ + +/*!< Endpoint-specific registers */ +/******************* Bit definition for USB_EP0R register *******************/ +#define USB_EP0R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP0R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP0R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP0R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP0R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP0R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP0R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP0R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP0R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP0R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP0R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP0R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP0R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP0R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP0R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP0R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP1R register *******************/ +#define USB_EP1R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP1R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP1R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP1R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP1R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP1R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP1R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP1R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP1R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP1R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP1R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP1R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP1R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP1R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP1R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP1R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP2R register *******************/ +#define USB_EP2R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP2R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP2R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP2R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP2R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP2R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP2R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP2R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP2R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP2R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP2R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP2R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP2R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP2R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP2R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP2R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP3R register *******************/ +#define USB_EP3R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP3R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP3R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP3R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP3R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP3R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP3R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP3R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP3R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP3R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP3R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP3R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP3R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP3R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP3R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP3R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP4R register *******************/ +#define USB_EP4R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP4R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP4R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP4R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP4R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP4R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP4R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP4R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP4R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP4R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP4R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP4R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP4R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP4R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP4R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP4R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP5R register *******************/ +#define USB_EP5R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP5R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP5R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP5R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP5R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP5R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP5R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP5R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP5R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP5R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP5R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP5R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP5R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP5R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP5R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP5R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP6R register *******************/ +#define USB_EP6R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP6R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP6R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP6R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP6R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP6R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP6R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP6R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP6R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP6R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP6R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP6R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP6R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP6R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP6R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP6R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/******************* Bit definition for USB_EP7R register *******************/ +#define USB_EP7R_EA ((uint16_t)0x000F) /*!< Endpoint Address */ + +#define USB_EP7R_STAT_TX ((uint16_t)0x0030) /*!< STAT_TX[1:0] bits (Status bits, for transmission transfers) */ +#define USB_EP7R_STAT_TX_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define USB_EP7R_STAT_TX_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define USB_EP7R_DTOG_TX ((uint16_t)0x0040) /*!< Data Toggle, for transmission transfers */ +#define USB_EP7R_CTR_TX ((uint16_t)0x0080) /*!< Correct Transfer for transmission */ +#define USB_EP7R_EP_KIND ((uint16_t)0x0100) /*!< Endpoint Kind */ + +#define USB_EP7R_EP_TYPE ((uint16_t)0x0600) /*!< EP_TYPE[1:0] bits (Endpoint type) */ +#define USB_EP7R_EP_TYPE_0 ((uint16_t)0x0200) /*!< Bit 0 */ +#define USB_EP7R_EP_TYPE_1 ((uint16_t)0x0400) /*!< Bit 1 */ + +#define USB_EP7R_SETUP ((uint16_t)0x0800) /*!< Setup transaction completed */ + +#define USB_EP7R_STAT_RX ((uint16_t)0x3000) /*!< STAT_RX[1:0] bits (Status bits, for reception transfers) */ +#define USB_EP7R_STAT_RX_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USB_EP7R_STAT_RX_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USB_EP7R_DTOG_RX ((uint16_t)0x4000) /*!< Data Toggle, for reception transfers */ +#define USB_EP7R_CTR_RX ((uint16_t)0x8000) /*!< Correct Transfer for reception */ + +/*!< Common registers */ +/******************* Bit definition for USB_CNTR register *******************/ +#define USB_CNTR_FRES ((uint16_t)0x0001) /*!< Force USB Reset */ +#define USB_CNTR_PDWN ((uint16_t)0x0002) /*!< Power down */ +#define USB_CNTR_LP_MODE ((uint16_t)0x0004) /*!< Low-power mode */ +#define USB_CNTR_FSUSP ((uint16_t)0x0008) /*!< Force suspend */ +#define USB_CNTR_RESUME ((uint16_t)0x0010) /*!< Resume request */ +#define USB_CNTR_ESOFM ((uint16_t)0x0100) /*!< Expected Start Of Frame Interrupt Mask */ +#define USB_CNTR_SOFM ((uint16_t)0x0200) /*!< Start Of Frame Interrupt Mask */ +#define USB_CNTR_RESETM ((uint16_t)0x0400) /*!< RESET Interrupt Mask */ +#define USB_CNTR_SUSPM ((uint16_t)0x0800) /*!< Suspend mode Interrupt Mask */ +#define USB_CNTR_WKUPM ((uint16_t)0x1000) /*!< Wakeup Interrupt Mask */ +#define USB_CNTR_ERRM ((uint16_t)0x2000) /*!< Error Interrupt Mask */ +#define USB_CNTR_PMAOVRM ((uint16_t)0x4000) /*!< Packet Memory Area Over / Underrun Interrupt Mask */ +#define USB_CNTR_CTRM ((uint16_t)0x8000) /*!< Correct Transfer Interrupt Mask */ + +/******************* Bit definition for USB_ISTR register *******************/ +#define USB_ISTR_EP_ID ((uint16_t)0x000F) /*!< Endpoint Identifier */ +#define USB_ISTR_DIR ((uint16_t)0x0010) /*!< Direction of transaction */ +#define USB_ISTR_ESOF ((uint16_t)0x0100) /*!< Expected Start Of Frame */ +#define USB_ISTR_SOF ((uint16_t)0x0200) /*!< Start Of Frame */ +#define USB_ISTR_RESET ((uint16_t)0x0400) /*!< USB RESET request */ +#define USB_ISTR_SUSP ((uint16_t)0x0800) /*!< Suspend mode request */ +#define USB_ISTR_WKUP ((uint16_t)0x1000) /*!< Wake up */ +#define USB_ISTR_ERR ((uint16_t)0x2000) /*!< Error */ +#define USB_ISTR_PMAOVR ((uint16_t)0x4000) /*!< Packet Memory Area Over / Underrun */ +#define USB_ISTR_CTR ((uint16_t)0x8000) /*!< Correct Transfer */ + +/******************* Bit definition for USB_FNR register ********************/ +#define USB_FNR_FN ((uint16_t)0x07FF) /*!< Frame Number */ +#define USB_FNR_LSOF ((uint16_t)0x1800) /*!< Lost SOF */ +#define USB_FNR_LCK ((uint16_t)0x2000) /*!< Locked */ +#define USB_FNR_RXDM ((uint16_t)0x4000) /*!< Receive Data - Line Status */ +#define USB_FNR_RXDP ((uint16_t)0x8000) /*!< Receive Data + Line Status */ + +/****************** Bit definition for USB_DADDR register *******************/ +#define USB_DADDR_ADD ((uint8_t)0x7F) /*!< ADD[6:0] bits (Device Address) */ +#define USB_DADDR_ADD0 ((uint8_t)0x01) /*!< Bit 0 */ +#define USB_DADDR_ADD1 ((uint8_t)0x02) /*!< Bit 1 */ +#define USB_DADDR_ADD2 ((uint8_t)0x04) /*!< Bit 2 */ +#define USB_DADDR_ADD3 ((uint8_t)0x08) /*!< Bit 3 */ +#define USB_DADDR_ADD4 ((uint8_t)0x10) /*!< Bit 4 */ +#define USB_DADDR_ADD5 ((uint8_t)0x20) /*!< Bit 5 */ +#define USB_DADDR_ADD6 ((uint8_t)0x40) /*!< Bit 6 */ + +#define USB_DADDR_EF ((uint8_t)0x80) /*!< Enable Function */ + +/****************** Bit definition for USB_BTABLE register ******************/ +#define USB_BTABLE_BTABLE ((uint16_t)0xFFF8) /*!< Buffer Table */ + +/*!< Buffer descriptor table */ +/***************** Bit definition for USB_ADDR0_TX register *****************/ +#define USB_ADDR0_TX_ADDR0_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 0 */ + +/***************** Bit definition for USB_ADDR1_TX register *****************/ +#define USB_ADDR1_TX_ADDR1_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 1 */ + +/***************** Bit definition for USB_ADDR2_TX register *****************/ +#define USB_ADDR2_TX_ADDR2_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 2 */ + +/***************** Bit definition for USB_ADDR3_TX register *****************/ +#define USB_ADDR3_TX_ADDR3_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 3 */ + +/***************** Bit definition for USB_ADDR4_TX register *****************/ +#define USB_ADDR4_TX_ADDR4_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 4 */ + +/***************** Bit definition for USB_ADDR5_TX register *****************/ +#define USB_ADDR5_TX_ADDR5_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 5 */ + +/***************** Bit definition for USB_ADDR6_TX register *****************/ +#define USB_ADDR6_TX_ADDR6_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 6 */ + +/***************** Bit definition for USB_ADDR7_TX register *****************/ +#define USB_ADDR7_TX_ADDR7_TX ((uint16_t)0xFFFE) /*!< Transmission Buffer Address 7 */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_COUNT0_TX register ****************/ +#define USB_COUNT0_TX_COUNT0_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 0 */ + +/***************** Bit definition for USB_COUNT1_TX register ****************/ +#define USB_COUNT1_TX_COUNT1_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 1 */ + +/***************** Bit definition for USB_COUNT2_TX register ****************/ +#define USB_COUNT2_TX_COUNT2_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 2 */ + +/***************** Bit definition for USB_COUNT3_TX register ****************/ +#define USB_COUNT3_TX_COUNT3_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 3 */ + +/***************** Bit definition for USB_COUNT4_TX register ****************/ +#define USB_COUNT4_TX_COUNT4_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 4 */ + +/***************** Bit definition for USB_COUNT5_TX register ****************/ +#define USB_COUNT5_TX_COUNT5_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 5 */ + +/***************** Bit definition for USB_COUNT6_TX register ****************/ +#define USB_COUNT6_TX_COUNT6_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 6 */ + +/***************** Bit definition for USB_COUNT7_TX register ****************/ +#define USB_COUNT7_TX_COUNT7_TX ((uint16_t)0x03FF) /*!< Transmission Byte Count 7 */ + +/*----------------------------------------------------------------------------*/ + +/**************** Bit definition for USB_COUNT0_TX_0 register ***************/ +#define USB_COUNT0_TX_0_COUNT0_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 0 (low) */ + +/**************** Bit definition for USB_COUNT0_TX_1 register ***************/ +#define USB_COUNT0_TX_1_COUNT0_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 0 (high) */ + +/**************** Bit definition for USB_COUNT1_TX_0 register ***************/ +#define USB_COUNT1_TX_0_COUNT1_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 1 (low) */ + +/**************** Bit definition for USB_COUNT1_TX_1 register ***************/ +#define USB_COUNT1_TX_1_COUNT1_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 1 (high) */ + +/**************** Bit definition for USB_COUNT2_TX_0 register ***************/ +#define USB_COUNT2_TX_0_COUNT2_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 2 (low) */ + +/**************** Bit definition for USB_COUNT2_TX_1 register ***************/ +#define USB_COUNT2_TX_1_COUNT2_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 2 (high) */ + +/**************** Bit definition for USB_COUNT3_TX_0 register ***************/ +#define USB_COUNT3_TX_0_COUNT3_TX_0 ((uint16_t)0x000003FF) /*!< Transmission Byte Count 3 (low) */ + +/**************** Bit definition for USB_COUNT3_TX_1 register ***************/ +#define USB_COUNT3_TX_1_COUNT3_TX_1 ((uint16_t)0x03FF0000) /*!< Transmission Byte Count 3 (high) */ + +/**************** Bit definition for USB_COUNT4_TX_0 register ***************/ +#define USB_COUNT4_TX_0_COUNT4_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 4 (low) */ + +/**************** Bit definition for USB_COUNT4_TX_1 register ***************/ +#define USB_COUNT4_TX_1_COUNT4_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 4 (high) */ + +/**************** Bit definition for USB_COUNT5_TX_0 register ***************/ +#define USB_COUNT5_TX_0_COUNT5_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 5 (low) */ + +/**************** Bit definition for USB_COUNT5_TX_1 register ***************/ +#define USB_COUNT5_TX_1_COUNT5_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 5 (high) */ + +/**************** Bit definition for USB_COUNT6_TX_0 register ***************/ +#define USB_COUNT6_TX_0_COUNT6_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 6 (low) */ + +/**************** Bit definition for USB_COUNT6_TX_1 register ***************/ +#define USB_COUNT6_TX_1_COUNT6_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 6 (high) */ + +/**************** Bit definition for USB_COUNT7_TX_0 register ***************/ +#define USB_COUNT7_TX_0_COUNT7_TX_0 ((uint32_t)0x000003FF) /*!< Transmission Byte Count 7 (low) */ + +/**************** Bit definition for USB_COUNT7_TX_1 register ***************/ +#define USB_COUNT7_TX_1_COUNT7_TX_1 ((uint32_t)0x03FF0000) /*!< Transmission Byte Count 7 (high) */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_ADDR0_RX register *****************/ +#define USB_ADDR0_RX_ADDR0_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 0 */ + +/***************** Bit definition for USB_ADDR1_RX register *****************/ +#define USB_ADDR1_RX_ADDR1_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 1 */ + +/***************** Bit definition for USB_ADDR2_RX register *****************/ +#define USB_ADDR2_RX_ADDR2_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 2 */ + +/***************** Bit definition for USB_ADDR3_RX register *****************/ +#define USB_ADDR3_RX_ADDR3_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 3 */ + +/***************** Bit definition for USB_ADDR4_RX register *****************/ +#define USB_ADDR4_RX_ADDR4_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 4 */ + +/***************** Bit definition for USB_ADDR5_RX register *****************/ +#define USB_ADDR5_RX_ADDR5_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 5 */ + +/***************** Bit definition for USB_ADDR6_RX register *****************/ +#define USB_ADDR6_RX_ADDR6_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 6 */ + +/***************** Bit definition for USB_ADDR7_RX register *****************/ +#define USB_ADDR7_RX_ADDR7_RX ((uint16_t)0xFFFE) /*!< Reception Buffer Address 7 */ + +/*----------------------------------------------------------------------------*/ + +/***************** Bit definition for USB_COUNT0_RX register ****************/ +#define USB_COUNT0_RX_COUNT0_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT0_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT0_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT0_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT0_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT0_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT0_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT1_RX register ****************/ +#define USB_COUNT1_RX_COUNT1_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT1_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT1_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT1_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT1_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT1_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT1_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT2_RX register ****************/ +#define USB_COUNT2_RX_COUNT2_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT2_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT2_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT2_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT2_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT2_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT2_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT3_RX register ****************/ +#define USB_COUNT3_RX_COUNT3_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT3_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT3_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT3_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT3_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT3_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT3_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT4_RX register ****************/ +#define USB_COUNT4_RX_COUNT4_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT4_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT4_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT4_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT4_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT4_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT4_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT5_RX register ****************/ +#define USB_COUNT5_RX_COUNT5_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT5_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT5_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT5_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT5_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT5_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT5_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT6_RX register ****************/ +#define USB_COUNT6_RX_COUNT6_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT6_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT6_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT6_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT6_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT6_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT6_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/***************** Bit definition for USB_COUNT7_RX register ****************/ +#define USB_COUNT7_RX_COUNT7_RX ((uint16_t)0x03FF) /*!< Reception Byte Count */ + +#define USB_COUNT7_RX_NUM_BLOCK ((uint16_t)0x7C00) /*!< NUM_BLOCK[4:0] bits (Number of blocks) */ +#define USB_COUNT7_RX_NUM_BLOCK_0 ((uint16_t)0x0400) /*!< Bit 0 */ +#define USB_COUNT7_RX_NUM_BLOCK_1 ((uint16_t)0x0800) /*!< Bit 1 */ +#define USB_COUNT7_RX_NUM_BLOCK_2 ((uint16_t)0x1000) /*!< Bit 2 */ +#define USB_COUNT7_RX_NUM_BLOCK_3 ((uint16_t)0x2000) /*!< Bit 3 */ +#define USB_COUNT7_RX_NUM_BLOCK_4 ((uint16_t)0x4000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_BLSIZE ((uint16_t)0x8000) /*!< BLock SIZE */ + +/*----------------------------------------------------------------------------*/ + +/**************** Bit definition for USB_COUNT0_RX_0 register ***************/ +#define USB_COUNT0_RX_0_COUNT0_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT0_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT0_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT0_RX_1 register ***************/ +#define USB_COUNT0_RX_1_COUNT0_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT0_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 1 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT0_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT0_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT1_RX_0 register ***************/ +#define USB_COUNT1_RX_0_COUNT1_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT1_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT1_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT1_RX_1 register ***************/ +#define USB_COUNT1_RX_1_COUNT1_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT1_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT1_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT1_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT2_RX_0 register ***************/ +#define USB_COUNT2_RX_0_COUNT2_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT2_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT2_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT2_RX_1 register ***************/ +#define USB_COUNT2_RX_1_COUNT2_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT2_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT2_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT2_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT3_RX_0 register ***************/ +#define USB_COUNT3_RX_0_COUNT3_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT3_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT3_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT3_RX_1 register ***************/ +#define USB_COUNT3_RX_1_COUNT3_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT3_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT3_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT3_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT4_RX_0 register ***************/ +#define USB_COUNT4_RX_0_COUNT4_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT4_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT4_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT4_RX_1 register ***************/ +#define USB_COUNT4_RX_1_COUNT4_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT4_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT4_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT4_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/**************** Bit definition for USB_COUNT5_RX_0 register ***************/ +#define USB_COUNT5_RX_0_COUNT5_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT5_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT5_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT5_RX_1 register ***************/ +#define USB_COUNT5_RX_1_COUNT5_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT5_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT5_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT5_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/*************** Bit definition for USB_COUNT6_RX_0 register ***************/ +#define USB_COUNT6_RX_0_COUNT6_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT6_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT6_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/**************** Bit definition for USB_COUNT6_RX_1 register ***************/ +#define USB_COUNT6_RX_1_COUNT6_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT6_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT6_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT6_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/*************** Bit definition for USB_COUNT7_RX_0 register ****************/ +#define USB_COUNT7_RX_0_COUNT7_RX_0 ((uint32_t)0x000003FF) /*!< Reception Byte Count (low) */ + +#define USB_COUNT7_RX_0_NUM_BLOCK_0 ((uint32_t)0x00007C00) /*!< NUM_BLOCK_0[4:0] bits (Number of blocks) (low) */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_0 ((uint32_t)0x00000400) /*!< Bit 0 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_1 ((uint32_t)0x00000800) /*!< Bit 1 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_2 ((uint32_t)0x00001000) /*!< Bit 2 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_3 ((uint32_t)0x00002000) /*!< Bit 3 */ +#define USB_COUNT7_RX_0_NUM_BLOCK_0_4 ((uint32_t)0x00004000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_0_BLSIZE_0 ((uint32_t)0x00008000) /*!< BLock SIZE (low) */ + +/*************** Bit definition for USB_COUNT7_RX_1 register ****************/ +#define USB_COUNT7_RX_1_COUNT7_RX_1 ((uint32_t)0x03FF0000) /*!< Reception Byte Count (high) */ + +#define USB_COUNT7_RX_1_NUM_BLOCK_1 ((uint32_t)0x7C000000) /*!< NUM_BLOCK_1[4:0] bits (Number of blocks) (high) */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_0 ((uint32_t)0x04000000) /*!< Bit 0 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_1 ((uint32_t)0x08000000) /*!< Bit 1 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_2 ((uint32_t)0x10000000) /*!< Bit 2 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_3 ((uint32_t)0x20000000) /*!< Bit 3 */ +#define USB_COUNT7_RX_1_NUM_BLOCK_1_4 ((uint32_t)0x40000000) /*!< Bit 4 */ + +#define USB_COUNT7_RX_1_BLSIZE_1 ((uint32_t)0x80000000) /*!< BLock SIZE (high) */ + +/******************************************************************************/ +/* */ +/* Controller Area Network */ +/* */ +/******************************************************************************/ + +/*!< CAN control and status registers */ +/******************* Bit definition for CAN_MCR register ********************/ +#define CAN_MCR_INRQ ((uint16_t)0x0001) /*!< Initialization Request */ +#define CAN_MCR_SLEEP ((uint16_t)0x0002) /*!< Sleep Mode Request */ +#define CAN_MCR_TXFP ((uint16_t)0x0004) /*!< Transmit FIFO Priority */ +#define CAN_MCR_RFLM ((uint16_t)0x0008) /*!< Receive FIFO Locked Mode */ +#define CAN_MCR_NART ((uint16_t)0x0010) /*!< No Automatic Retransmission */ +#define CAN_MCR_AWUM ((uint16_t)0x0020) /*!< Automatic Wakeup Mode */ +#define CAN_MCR_ABOM ((uint16_t)0x0040) /*!< Automatic Bus-Off Management */ +#define CAN_MCR_TTCM ((uint16_t)0x0080) /*!< Time Triggered Communication Mode */ +#define CAN_MCR_RESET ((uint16_t)0x8000) /*!< CAN software master reset */ + +/******************* Bit definition for CAN_MSR register ********************/ +#define CAN_MSR_INAK ((uint16_t)0x0001) /*!< Initialization Acknowledge */ +#define CAN_MSR_SLAK ((uint16_t)0x0002) /*!< Sleep Acknowledge */ +#define CAN_MSR_ERRI ((uint16_t)0x0004) /*!< Error Interrupt */ +#define CAN_MSR_WKUI ((uint16_t)0x0008) /*!< Wakeup Interrupt */ +#define CAN_MSR_SLAKI ((uint16_t)0x0010) /*!< Sleep Acknowledge Interrupt */ +#define CAN_MSR_TXM ((uint16_t)0x0100) /*!< Transmit Mode */ +#define CAN_MSR_RXM ((uint16_t)0x0200) /*!< Receive Mode */ +#define CAN_MSR_SAMP ((uint16_t)0x0400) /*!< Last Sample Point */ +#define CAN_MSR_RX ((uint16_t)0x0800) /*!< CAN Rx Signal */ + +/******************* Bit definition for CAN_TSR register ********************/ +#define CAN_TSR_RQCP0 ((uint32_t)0x00000001) /*!< Request Completed Mailbox0 */ +#define CAN_TSR_TXOK0 ((uint32_t)0x00000002) /*!< Transmission OK of Mailbox0 */ +#define CAN_TSR_ALST0 ((uint32_t)0x00000004) /*!< Arbitration Lost for Mailbox0 */ +#define CAN_TSR_TERR0 ((uint32_t)0x00000008) /*!< Transmission Error of Mailbox0 */ +#define CAN_TSR_ABRQ0 ((uint32_t)0x00000080) /*!< Abort Request for Mailbox0 */ +#define CAN_TSR_RQCP1 ((uint32_t)0x00000100) /*!< Request Completed Mailbox1 */ +#define CAN_TSR_TXOK1 ((uint32_t)0x00000200) /*!< Transmission OK of Mailbox1 */ +#define CAN_TSR_ALST1 ((uint32_t)0x00000400) /*!< Arbitration Lost for Mailbox1 */ +#define CAN_TSR_TERR1 ((uint32_t)0x00000800) /*!< Transmission Error of Mailbox1 */ +#define CAN_TSR_ABRQ1 ((uint32_t)0x00008000) /*!< Abort Request for Mailbox 1 */ +#define CAN_TSR_RQCP2 ((uint32_t)0x00010000) /*!< Request Completed Mailbox2 */ +#define CAN_TSR_TXOK2 ((uint32_t)0x00020000) /*!< Transmission OK of Mailbox 2 */ +#define CAN_TSR_ALST2 ((uint32_t)0x00040000) /*!< Arbitration Lost for mailbox 2 */ +#define CAN_TSR_TERR2 ((uint32_t)0x00080000) /*!< Transmission Error of Mailbox 2 */ +#define CAN_TSR_ABRQ2 ((uint32_t)0x00800000) /*!< Abort Request for Mailbox 2 */ +#define CAN_TSR_CODE ((uint32_t)0x03000000) /*!< Mailbox Code */ + +#define CAN_TSR_TME ((uint32_t)0x1C000000) /*!< TME[2:0] bits */ +#define CAN_TSR_TME0 ((uint32_t)0x04000000) /*!< Transmit Mailbox 0 Empty */ +#define CAN_TSR_TME1 ((uint32_t)0x08000000) /*!< Transmit Mailbox 1 Empty */ +#define CAN_TSR_TME2 ((uint32_t)0x10000000) /*!< Transmit Mailbox 2 Empty */ + +#define CAN_TSR_LOW ((uint32_t)0xE0000000) /*!< LOW[2:0] bits */ +#define CAN_TSR_LOW0 ((uint32_t)0x20000000) /*!< Lowest Priority Flag for Mailbox 0 */ +#define CAN_TSR_LOW1 ((uint32_t)0x40000000) /*!< Lowest Priority Flag for Mailbox 1 */ +#define CAN_TSR_LOW2 ((uint32_t)0x80000000) /*!< Lowest Priority Flag for Mailbox 2 */ + +/******************* Bit definition for CAN_RF0R register *******************/ +#define CAN_RF0R_FMP0 ((uint8_t)0x03) /*!< FIFO 0 Message Pending */ +#define CAN_RF0R_FULL0 ((uint8_t)0x08) /*!< FIFO 0 Full */ +#define CAN_RF0R_FOVR0 ((uint8_t)0x10) /*!< FIFO 0 Overrun */ +#define CAN_RF0R_RFOM0 ((uint8_t)0x20) /*!< Release FIFO 0 Output Mailbox */ + +/******************* Bit definition for CAN_RF1R register *******************/ +#define CAN_RF1R_FMP1 ((uint8_t)0x03) /*!< FIFO 1 Message Pending */ +#define CAN_RF1R_FULL1 ((uint8_t)0x08) /*!< FIFO 1 Full */ +#define CAN_RF1R_FOVR1 ((uint8_t)0x10) /*!< FIFO 1 Overrun */ +#define CAN_RF1R_RFOM1 ((uint8_t)0x20) /*!< Release FIFO 1 Output Mailbox */ + +/******************** Bit definition for CAN_IER register *******************/ +#define CAN_IER_TMEIE ((uint32_t)0x00000001) /*!< Transmit Mailbox Empty Interrupt Enable */ +#define CAN_IER_FMPIE0 ((uint32_t)0x00000002) /*!< FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE0 ((uint32_t)0x00000004) /*!< FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE0 ((uint32_t)0x00000008) /*!< FIFO Overrun Interrupt Enable */ +#define CAN_IER_FMPIE1 ((uint32_t)0x00000010) /*!< FIFO Message Pending Interrupt Enable */ +#define CAN_IER_FFIE1 ((uint32_t)0x00000020) /*!< FIFO Full Interrupt Enable */ +#define CAN_IER_FOVIE1 ((uint32_t)0x00000040) /*!< FIFO Overrun Interrupt Enable */ +#define CAN_IER_EWGIE ((uint32_t)0x00000100) /*!< Error Warning Interrupt Enable */ +#define CAN_IER_EPVIE ((uint32_t)0x00000200) /*!< Error Passive Interrupt Enable */ +#define CAN_IER_BOFIE ((uint32_t)0x00000400) /*!< Bus-Off Interrupt Enable */ +#define CAN_IER_LECIE ((uint32_t)0x00000800) /*!< Last Error Code Interrupt Enable */ +#define CAN_IER_ERRIE ((uint32_t)0x00008000) /*!< Error Interrupt Enable */ +#define CAN_IER_WKUIE ((uint32_t)0x00010000) /*!< Wakeup Interrupt Enable */ +#define CAN_IER_SLKIE ((uint32_t)0x00020000) /*!< Sleep Interrupt Enable */ + +/******************** Bit definition for CAN_ESR register *******************/ +#define CAN_ESR_EWGF ((uint32_t)0x00000001) /*!< Error Warning Flag */ +#define CAN_ESR_EPVF ((uint32_t)0x00000002) /*!< Error Passive Flag */ +#define CAN_ESR_BOFF ((uint32_t)0x00000004) /*!< Bus-Off Flag */ + +#define CAN_ESR_LEC ((uint32_t)0x00000070) /*!< LEC[2:0] bits (Last Error Code) */ +#define CAN_ESR_LEC_0 ((uint32_t)0x00000010) /*!< Bit 0 */ +#define CAN_ESR_LEC_1 ((uint32_t)0x00000020) /*!< Bit 1 */ +#define CAN_ESR_LEC_2 ((uint32_t)0x00000040) /*!< Bit 2 */ + +#define CAN_ESR_TEC ((uint32_t)0x00FF0000) /*!< Least significant byte of the 9-bit Transmit Error Counter */ +#define CAN_ESR_REC ((uint32_t)0xFF000000) /*!< Receive Error Counter */ + +/******************* Bit definition for CAN_BTR register ********************/ +#define CAN_BTR_BRP ((uint32_t)0x000003FF) /*!< Baud Rate Prescaler */ +#define CAN_BTR_TS1 ((uint32_t)0x000F0000) /*!< Time Segment 1 */ +#define CAN_BTR_TS2 ((uint32_t)0x00700000) /*!< Time Segment 2 */ +#define CAN_BTR_SJW ((uint32_t)0x03000000) /*!< Resynchronization Jump Width */ +#define CAN_BTR_LBKM ((uint32_t)0x40000000) /*!< Loop Back Mode (Debug) */ +#define CAN_BTR_SILM ((uint32_t)0x80000000) /*!< Silent Mode */ + +/*!< Mailbox registers */ +/****************** Bit definition for CAN_TI0R register ********************/ +#define CAN_TI0R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI0R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI0R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI0R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_TI0R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/****************** Bit definition for CAN_TDT0R register *******************/ +#define CAN_TDT0R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT0R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT0R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/****************** Bit definition for CAN_TDL0R register *******************/ +#define CAN_TDL0R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL0R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL0R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL0R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/****************** Bit definition for CAN_TDH0R register *******************/ +#define CAN_TDH0R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH0R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH0R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH0R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_TI1R register *******************/ +#define CAN_TI1R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI1R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI1R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI1R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_TI1R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_TDT1R register ******************/ +#define CAN_TDT1R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT1R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT1R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_TDL1R register ******************/ +#define CAN_TDL1R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL1R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL1R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL1R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_TDH1R register ******************/ +#define CAN_TDH1R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH1R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH1R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH1R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_TI2R register *******************/ +#define CAN_TI2R_TXRQ ((uint32_t)0x00000001) /*!< Transmit Mailbox Request */ +#define CAN_TI2R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_TI2R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_TI2R_EXID ((uint32_t)0x001FFFF8) /*!< Extended identifier */ +#define CAN_TI2R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_TDT2R register ******************/ +#define CAN_TDT2R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_TDT2R_TGT ((uint32_t)0x00000100) /*!< Transmit Global Time */ +#define CAN_TDT2R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_TDL2R register ******************/ +#define CAN_TDL2R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_TDL2R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_TDL2R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_TDL2R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_TDH2R register ******************/ +#define CAN_TDH2R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_TDH2R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_TDH2R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_TDH2R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_RI0R register *******************/ +#define CAN_RI0R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_RI0R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_RI0R_EXID ((uint32_t)0x001FFFF8) /*!< Extended Identifier */ +#define CAN_RI0R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_RDT0R register ******************/ +#define CAN_RDT0R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_RDT0R_FMI ((uint32_t)0x0000FF00) /*!< Filter Match Index */ +#define CAN_RDT0R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_RDL0R register ******************/ +#define CAN_RDL0R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_RDL0R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_RDL0R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_RDL0R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_RDH0R register ******************/ +#define CAN_RDH0R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_RDH0R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_RDH0R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_RDH0R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/******************* Bit definition for CAN_RI1R register *******************/ +#define CAN_RI1R_RTR ((uint32_t)0x00000002) /*!< Remote Transmission Request */ +#define CAN_RI1R_IDE ((uint32_t)0x00000004) /*!< Identifier Extension */ +#define CAN_RI1R_EXID ((uint32_t)0x001FFFF8) /*!< Extended identifier */ +#define CAN_RI1R_STID ((uint32_t)0xFFE00000) /*!< Standard Identifier or Extended Identifier */ + +/******************* Bit definition for CAN_RDT1R register ******************/ +#define CAN_RDT1R_DLC ((uint32_t)0x0000000F) /*!< Data Length Code */ +#define CAN_RDT1R_FMI ((uint32_t)0x0000FF00) /*!< Filter Match Index */ +#define CAN_RDT1R_TIME ((uint32_t)0xFFFF0000) /*!< Message Time Stamp */ + +/******************* Bit definition for CAN_RDL1R register ******************/ +#define CAN_RDL1R_DATA0 ((uint32_t)0x000000FF) /*!< Data byte 0 */ +#define CAN_RDL1R_DATA1 ((uint32_t)0x0000FF00) /*!< Data byte 1 */ +#define CAN_RDL1R_DATA2 ((uint32_t)0x00FF0000) /*!< Data byte 2 */ +#define CAN_RDL1R_DATA3 ((uint32_t)0xFF000000) /*!< Data byte 3 */ + +/******************* Bit definition for CAN_RDH1R register ******************/ +#define CAN_RDH1R_DATA4 ((uint32_t)0x000000FF) /*!< Data byte 4 */ +#define CAN_RDH1R_DATA5 ((uint32_t)0x0000FF00) /*!< Data byte 5 */ +#define CAN_RDH1R_DATA6 ((uint32_t)0x00FF0000) /*!< Data byte 6 */ +#define CAN_RDH1R_DATA7 ((uint32_t)0xFF000000) /*!< Data byte 7 */ + +/*!< CAN filter registers */ +/******************* Bit definition for CAN_FMR register ********************/ +#define CAN_FMR_FINIT ((uint8_t)0x01) /*!< Filter Init Mode */ + +/******************* Bit definition for CAN_FM1R register *******************/ +#define CAN_FM1R_FBM ((uint16_t)0x3FFF) /*!< Filter Mode */ +#define CAN_FM1R_FBM0 ((uint16_t)0x0001) /*!< Filter Init Mode bit 0 */ +#define CAN_FM1R_FBM1 ((uint16_t)0x0002) /*!< Filter Init Mode bit 1 */ +#define CAN_FM1R_FBM2 ((uint16_t)0x0004) /*!< Filter Init Mode bit 2 */ +#define CAN_FM1R_FBM3 ((uint16_t)0x0008) /*!< Filter Init Mode bit 3 */ +#define CAN_FM1R_FBM4 ((uint16_t)0x0010) /*!< Filter Init Mode bit 4 */ +#define CAN_FM1R_FBM5 ((uint16_t)0x0020) /*!< Filter Init Mode bit 5 */ +#define CAN_FM1R_FBM6 ((uint16_t)0x0040) /*!< Filter Init Mode bit 6 */ +#define CAN_FM1R_FBM7 ((uint16_t)0x0080) /*!< Filter Init Mode bit 7 */ +#define CAN_FM1R_FBM8 ((uint16_t)0x0100) /*!< Filter Init Mode bit 8 */ +#define CAN_FM1R_FBM9 ((uint16_t)0x0200) /*!< Filter Init Mode bit 9 */ +#define CAN_FM1R_FBM10 ((uint16_t)0x0400) /*!< Filter Init Mode bit 10 */ +#define CAN_FM1R_FBM11 ((uint16_t)0x0800) /*!< Filter Init Mode bit 11 */ +#define CAN_FM1R_FBM12 ((uint16_t)0x1000) /*!< Filter Init Mode bit 12 */ +#define CAN_FM1R_FBM13 ((uint16_t)0x2000) /*!< Filter Init Mode bit 13 */ + +/******************* Bit definition for CAN_FS1R register *******************/ +#define CAN_FS1R_FSC ((uint16_t)0x3FFF) /*!< Filter Scale Configuration */ +#define CAN_FS1R_FSC0 ((uint16_t)0x0001) /*!< Filter Scale Configuration bit 0 */ +#define CAN_FS1R_FSC1 ((uint16_t)0x0002) /*!< Filter Scale Configuration bit 1 */ +#define CAN_FS1R_FSC2 ((uint16_t)0x0004) /*!< Filter Scale Configuration bit 2 */ +#define CAN_FS1R_FSC3 ((uint16_t)0x0008) /*!< Filter Scale Configuration bit 3 */ +#define CAN_FS1R_FSC4 ((uint16_t)0x0010) /*!< Filter Scale Configuration bit 4 */ +#define CAN_FS1R_FSC5 ((uint16_t)0x0020) /*!< Filter Scale Configuration bit 5 */ +#define CAN_FS1R_FSC6 ((uint16_t)0x0040) /*!< Filter Scale Configuration bit 6 */ +#define CAN_FS1R_FSC7 ((uint16_t)0x0080) /*!< Filter Scale Configuration bit 7 */ +#define CAN_FS1R_FSC8 ((uint16_t)0x0100) /*!< Filter Scale Configuration bit 8 */ +#define CAN_FS1R_FSC9 ((uint16_t)0x0200) /*!< Filter Scale Configuration bit 9 */ +#define CAN_FS1R_FSC10 ((uint16_t)0x0400) /*!< Filter Scale Configuration bit 10 */ +#define CAN_FS1R_FSC11 ((uint16_t)0x0800) /*!< Filter Scale Configuration bit 11 */ +#define CAN_FS1R_FSC12 ((uint16_t)0x1000) /*!< Filter Scale Configuration bit 12 */ +#define CAN_FS1R_FSC13 ((uint16_t)0x2000) /*!< Filter Scale Configuration bit 13 */ + +/****************** Bit definition for CAN_FFA1R register *******************/ +#define CAN_FFA1R_FFA ((uint16_t)0x3FFF) /*!< Filter FIFO Assignment */ +#define CAN_FFA1R_FFA0 ((uint16_t)0x0001) /*!< Filter FIFO Assignment for Filter 0 */ +#define CAN_FFA1R_FFA1 ((uint16_t)0x0002) /*!< Filter FIFO Assignment for Filter 1 */ +#define CAN_FFA1R_FFA2 ((uint16_t)0x0004) /*!< Filter FIFO Assignment for Filter 2 */ +#define CAN_FFA1R_FFA3 ((uint16_t)0x0008) /*!< Filter FIFO Assignment for Filter 3 */ +#define CAN_FFA1R_FFA4 ((uint16_t)0x0010) /*!< Filter FIFO Assignment for Filter 4 */ +#define CAN_FFA1R_FFA5 ((uint16_t)0x0020) /*!< Filter FIFO Assignment for Filter 5 */ +#define CAN_FFA1R_FFA6 ((uint16_t)0x0040) /*!< Filter FIFO Assignment for Filter 6 */ +#define CAN_FFA1R_FFA7 ((uint16_t)0x0080) /*!< Filter FIFO Assignment for Filter 7 */ +#define CAN_FFA1R_FFA8 ((uint16_t)0x0100) /*!< Filter FIFO Assignment for Filter 8 */ +#define CAN_FFA1R_FFA9 ((uint16_t)0x0200) /*!< Filter FIFO Assignment for Filter 9 */ +#define CAN_FFA1R_FFA10 ((uint16_t)0x0400) /*!< Filter FIFO Assignment for Filter 10 */ +#define CAN_FFA1R_FFA11 ((uint16_t)0x0800) /*!< Filter FIFO Assignment for Filter 11 */ +#define CAN_FFA1R_FFA12 ((uint16_t)0x1000) /*!< Filter FIFO Assignment for Filter 12 */ +#define CAN_FFA1R_FFA13 ((uint16_t)0x2000) /*!< Filter FIFO Assignment for Filter 13 */ + +/******************* Bit definition for CAN_FA1R register *******************/ +#define CAN_FA1R_FACT ((uint16_t)0x3FFF) /*!< Filter Active */ +#define CAN_FA1R_FACT0 ((uint16_t)0x0001) /*!< Filter 0 Active */ +#define CAN_FA1R_FACT1 ((uint16_t)0x0002) /*!< Filter 1 Active */ +#define CAN_FA1R_FACT2 ((uint16_t)0x0004) /*!< Filter 2 Active */ +#define CAN_FA1R_FACT3 ((uint16_t)0x0008) /*!< Filter 3 Active */ +#define CAN_FA1R_FACT4 ((uint16_t)0x0010) /*!< Filter 4 Active */ +#define CAN_FA1R_FACT5 ((uint16_t)0x0020) /*!< Filter 5 Active */ +#define CAN_FA1R_FACT6 ((uint16_t)0x0040) /*!< Filter 6 Active */ +#define CAN_FA1R_FACT7 ((uint16_t)0x0080) /*!< Filter 7 Active */ +#define CAN_FA1R_FACT8 ((uint16_t)0x0100) /*!< Filter 8 Active */ +#define CAN_FA1R_FACT9 ((uint16_t)0x0200) /*!< Filter 9 Active */ +#define CAN_FA1R_FACT10 ((uint16_t)0x0400) /*!< Filter 10 Active */ +#define CAN_FA1R_FACT11 ((uint16_t)0x0800) /*!< Filter 11 Active */ +#define CAN_FA1R_FACT12 ((uint16_t)0x1000) /*!< Filter 12 Active */ +#define CAN_FA1R_FACT13 ((uint16_t)0x2000) /*!< Filter 13 Active */ + +/******************* Bit definition for CAN_F0R1 register *******************/ +#define CAN_F0R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F0R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F0R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F0R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F0R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F0R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F0R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F0R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F0R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F0R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F0R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F0R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F0R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F0R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F0R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F0R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F0R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F0R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F0R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F0R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F0R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F0R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F0R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F0R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F0R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F0R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F0R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F0R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F0R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F0R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F0R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F0R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F1R1 register *******************/ +#define CAN_F1R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F1R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F1R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F1R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F1R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F1R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F1R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F1R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F1R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F1R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F1R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F1R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F1R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F1R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F1R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F1R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F1R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F1R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F1R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F1R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F1R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F1R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F1R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F1R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F1R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F1R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F1R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F1R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F1R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F1R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F1R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F1R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F2R1 register *******************/ +#define CAN_F2R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F2R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F2R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F2R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F2R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F2R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F2R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F2R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F2R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F2R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F2R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F2R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F2R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F2R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F2R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F2R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F2R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F2R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F2R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F2R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F2R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F2R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F2R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F2R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F2R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F2R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F2R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F2R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F2R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F2R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F2R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F2R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F3R1 register *******************/ +#define CAN_F3R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F3R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F3R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F3R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F3R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F3R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F3R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F3R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F3R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F3R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F3R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F3R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F3R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F3R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F3R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F3R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F3R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F3R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F3R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F3R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F3R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F3R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F3R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F3R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F3R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F3R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F3R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F3R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F3R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F3R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F3R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F3R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F4R1 register *******************/ +#define CAN_F4R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F4R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F4R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F4R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F4R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F4R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F4R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F4R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F4R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F4R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F4R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F4R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F4R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F4R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F4R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F4R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F4R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F4R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F4R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F4R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F4R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F4R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F4R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F4R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F4R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F4R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F4R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F4R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F4R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F4R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F4R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F4R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F5R1 register *******************/ +#define CAN_F5R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F5R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F5R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F5R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F5R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F5R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F5R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F5R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F5R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F5R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F5R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F5R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F5R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F5R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F5R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F5R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F5R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F5R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F5R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F5R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F5R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F5R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F5R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F5R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F5R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F5R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F5R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F5R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F5R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F5R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F5R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F5R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F6R1 register *******************/ +#define CAN_F6R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F6R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F6R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F6R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F6R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F6R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F6R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F6R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F6R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F6R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F6R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F6R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F6R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F6R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F6R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F6R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F6R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F6R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F6R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F6R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F6R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F6R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F6R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F6R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F6R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F6R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F6R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F6R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F6R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F6R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F6R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F6R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F7R1 register *******************/ +#define CAN_F7R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F7R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F7R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F7R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F7R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F7R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F7R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F7R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F7R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F7R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F7R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F7R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F7R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F7R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F7R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F7R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F7R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F7R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F7R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F7R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F7R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F7R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F7R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F7R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F7R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F7R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F7R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F7R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F7R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F7R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F7R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F7R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F8R1 register *******************/ +#define CAN_F8R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F8R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F8R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F8R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F8R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F8R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F8R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F8R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F8R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F8R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F8R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F8R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F8R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F8R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F8R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F8R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F8R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F8R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F8R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F8R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F8R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F8R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F8R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F8R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F8R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F8R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F8R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F8R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F8R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F8R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F8R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F8R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F9R1 register *******************/ +#define CAN_F9R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F9R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F9R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F9R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F9R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F9R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F9R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F9R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F9R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F9R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F9R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F9R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F9R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F9R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F9R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F9R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F9R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F9R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F9R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F9R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F9R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F9R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F9R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F9R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F9R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F9R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F9R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F9R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F9R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F9R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F9R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F9R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F10R1 register ******************/ +#define CAN_F10R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F10R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F10R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F10R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F10R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F10R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F10R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F10R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F10R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F10R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F10R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F10R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F10R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F10R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F10R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F10R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F10R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F10R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F10R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F10R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F10R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F10R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F10R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F10R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F10R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F10R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F10R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F10R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F10R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F10R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F10R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F10R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F11R1 register ******************/ +#define CAN_F11R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F11R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F11R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F11R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F11R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F11R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F11R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F11R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F11R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F11R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F11R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F11R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F11R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F11R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F11R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F11R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F11R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F11R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F11R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F11R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F11R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F11R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F11R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F11R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F11R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F11R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F11R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F11R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F11R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F11R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F11R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F11R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F12R1 register ******************/ +#define CAN_F12R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F12R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F12R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F12R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F12R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F12R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F12R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F12R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F12R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F12R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F12R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F12R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F12R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F12R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F12R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F12R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F12R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F12R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F12R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F12R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F12R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F12R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F12R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F12R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F12R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F12R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F12R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F12R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F12R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F12R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F12R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F12R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F13R1 register ******************/ +#define CAN_F13R1_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F13R1_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F13R1_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F13R1_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F13R1_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F13R1_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F13R1_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F13R1_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F13R1_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F13R1_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F13R1_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F13R1_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F13R1_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F13R1_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F13R1_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F13R1_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F13R1_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F13R1_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F13R1_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F13R1_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F13R1_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F13R1_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F13R1_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F13R1_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F13R1_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F13R1_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F13R1_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F13R1_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F13R1_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F13R1_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F13R1_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F13R1_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F0R2 register *******************/ +#define CAN_F0R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F0R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F0R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F0R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F0R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F0R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F0R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F0R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F0R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F0R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F0R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F0R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F0R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F0R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F0R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F0R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F0R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F0R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F0R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F0R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F0R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F0R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F0R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F0R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F0R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F0R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F0R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F0R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F0R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F0R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F0R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F0R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F1R2 register *******************/ +#define CAN_F1R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F1R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F1R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F1R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F1R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F1R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F1R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F1R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F1R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F1R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F1R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F1R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F1R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F1R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F1R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F1R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F1R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F1R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F1R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F1R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F1R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F1R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F1R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F1R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F1R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F1R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F1R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F1R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F1R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F1R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F1R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F1R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F2R2 register *******************/ +#define CAN_F2R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F2R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F2R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F2R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F2R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F2R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F2R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F2R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F2R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F2R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F2R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F2R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F2R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F2R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F2R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F2R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F2R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F2R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F2R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F2R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F2R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F2R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F2R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F2R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F2R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F2R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F2R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F2R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F2R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F2R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F2R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F2R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F3R2 register *******************/ +#define CAN_F3R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F3R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F3R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F3R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F3R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F3R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F3R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F3R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F3R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F3R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F3R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F3R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F3R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F3R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F3R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F3R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F3R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F3R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F3R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F3R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F3R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F3R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F3R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F3R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F3R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F3R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F3R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F3R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F3R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F3R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F3R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F3R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F4R2 register *******************/ +#define CAN_F4R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F4R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F4R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F4R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F4R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F4R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F4R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F4R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F4R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F4R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F4R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F4R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F4R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F4R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F4R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F4R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F4R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F4R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F4R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F4R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F4R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F4R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F4R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F4R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F4R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F4R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F4R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F4R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F4R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F4R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F4R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F4R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F5R2 register *******************/ +#define CAN_F5R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F5R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F5R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F5R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F5R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F5R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F5R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F5R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F5R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F5R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F5R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F5R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F5R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F5R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F5R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F5R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F5R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F5R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F5R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F5R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F5R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F5R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F5R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F5R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F5R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F5R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F5R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F5R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F5R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F5R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F5R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F5R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F6R2 register *******************/ +#define CAN_F6R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F6R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F6R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F6R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F6R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F6R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F6R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F6R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F6R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F6R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F6R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F6R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F6R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F6R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F6R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F6R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F6R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F6R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F6R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F6R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F6R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F6R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F6R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F6R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F6R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F6R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F6R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F6R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F6R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F6R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F6R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F6R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F7R2 register *******************/ +#define CAN_F7R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F7R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F7R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F7R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F7R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F7R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F7R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F7R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F7R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F7R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F7R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F7R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F7R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F7R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F7R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F7R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F7R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F7R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F7R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F7R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F7R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F7R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F7R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F7R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F7R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F7R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F7R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F7R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F7R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F7R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F7R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F7R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F8R2 register *******************/ +#define CAN_F8R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F8R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F8R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F8R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F8R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F8R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F8R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F8R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F8R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F8R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F8R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F8R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F8R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F8R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F8R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F8R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F8R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F8R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F8R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F8R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F8R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F8R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F8R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F8R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F8R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F8R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F8R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F8R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F8R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F8R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F8R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F8R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F9R2 register *******************/ +#define CAN_F9R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F9R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F9R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F9R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F9R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F9R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F9R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F9R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F9R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F9R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F9R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F9R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F9R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F9R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F9R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F9R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F9R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F9R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F9R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F9R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F9R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F9R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F9R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F9R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F9R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F9R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F9R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F9R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F9R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F9R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F9R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F9R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F10R2 register ******************/ +#define CAN_F10R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F10R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F10R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F10R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F10R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F10R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F10R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F10R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F10R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F10R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F10R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F10R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F10R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F10R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F10R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F10R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F10R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F10R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F10R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F10R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F10R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F10R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F10R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F10R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F10R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F10R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F10R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F10R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F10R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F10R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F10R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F10R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F11R2 register ******************/ +#define CAN_F11R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F11R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F11R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F11R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F11R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F11R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F11R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F11R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F11R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F11R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F11R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F11R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F11R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F11R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F11R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F11R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F11R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F11R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F11R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F11R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F11R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F11R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F11R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F11R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F11R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F11R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F11R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F11R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F11R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F11R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F11R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F11R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F12R2 register ******************/ +#define CAN_F12R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F12R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F12R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F12R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F12R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F12R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F12R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F12R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F12R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F12R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F12R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F12R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F12R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F12R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F12R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F12R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F12R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F12R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F12R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F12R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F12R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F12R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F12R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F12R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F12R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F12R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F12R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F12R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F12R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F12R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F12R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F12R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************* Bit definition for CAN_F13R2 register ******************/ +#define CAN_F13R2_FB0 ((uint32_t)0x00000001) /*!< Filter bit 0 */ +#define CAN_F13R2_FB1 ((uint32_t)0x00000002) /*!< Filter bit 1 */ +#define CAN_F13R2_FB2 ((uint32_t)0x00000004) /*!< Filter bit 2 */ +#define CAN_F13R2_FB3 ((uint32_t)0x00000008) /*!< Filter bit 3 */ +#define CAN_F13R2_FB4 ((uint32_t)0x00000010) /*!< Filter bit 4 */ +#define CAN_F13R2_FB5 ((uint32_t)0x00000020) /*!< Filter bit 5 */ +#define CAN_F13R2_FB6 ((uint32_t)0x00000040) /*!< Filter bit 6 */ +#define CAN_F13R2_FB7 ((uint32_t)0x00000080) /*!< Filter bit 7 */ +#define CAN_F13R2_FB8 ((uint32_t)0x00000100) /*!< Filter bit 8 */ +#define CAN_F13R2_FB9 ((uint32_t)0x00000200) /*!< Filter bit 9 */ +#define CAN_F13R2_FB10 ((uint32_t)0x00000400) /*!< Filter bit 10 */ +#define CAN_F13R2_FB11 ((uint32_t)0x00000800) /*!< Filter bit 11 */ +#define CAN_F13R2_FB12 ((uint32_t)0x00001000) /*!< Filter bit 12 */ +#define CAN_F13R2_FB13 ((uint32_t)0x00002000) /*!< Filter bit 13 */ +#define CAN_F13R2_FB14 ((uint32_t)0x00004000) /*!< Filter bit 14 */ +#define CAN_F13R2_FB15 ((uint32_t)0x00008000) /*!< Filter bit 15 */ +#define CAN_F13R2_FB16 ((uint32_t)0x00010000) /*!< Filter bit 16 */ +#define CAN_F13R2_FB17 ((uint32_t)0x00020000) /*!< Filter bit 17 */ +#define CAN_F13R2_FB18 ((uint32_t)0x00040000) /*!< Filter bit 18 */ +#define CAN_F13R2_FB19 ((uint32_t)0x00080000) /*!< Filter bit 19 */ +#define CAN_F13R2_FB20 ((uint32_t)0x00100000) /*!< Filter bit 20 */ +#define CAN_F13R2_FB21 ((uint32_t)0x00200000) /*!< Filter bit 21 */ +#define CAN_F13R2_FB22 ((uint32_t)0x00400000) /*!< Filter bit 22 */ +#define CAN_F13R2_FB23 ((uint32_t)0x00800000) /*!< Filter bit 23 */ +#define CAN_F13R2_FB24 ((uint32_t)0x01000000) /*!< Filter bit 24 */ +#define CAN_F13R2_FB25 ((uint32_t)0x02000000) /*!< Filter bit 25 */ +#define CAN_F13R2_FB26 ((uint32_t)0x04000000) /*!< Filter bit 26 */ +#define CAN_F13R2_FB27 ((uint32_t)0x08000000) /*!< Filter bit 27 */ +#define CAN_F13R2_FB28 ((uint32_t)0x10000000) /*!< Filter bit 28 */ +#define CAN_F13R2_FB29 ((uint32_t)0x20000000) /*!< Filter bit 29 */ +#define CAN_F13R2_FB30 ((uint32_t)0x40000000) /*!< Filter bit 30 */ +#define CAN_F13R2_FB31 ((uint32_t)0x80000000) /*!< Filter bit 31 */ + +/******************************************************************************/ +/* */ +/* Serial Peripheral Interface */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for SPI_CR1 register ********************/ +#define SPI_CR1_CPHA ((uint16_t)0x0001) /*!< Clock Phase */ +#define SPI_CR1_CPOL ((uint16_t)0x0002) /*!< Clock Polarity */ +#define SPI_CR1_MSTR ((uint16_t)0x0004) /*!< Master Selection */ + +#define SPI_CR1_BR ((uint16_t)0x0038) /*!< BR[2:0] bits (Baud Rate Control) */ +#define SPI_CR1_BR_0 ((uint16_t)0x0008) /*!< Bit 0 */ +#define SPI_CR1_BR_1 ((uint16_t)0x0010) /*!< Bit 1 */ +#define SPI_CR1_BR_2 ((uint16_t)0x0020) /*!< Bit 2 */ + +#define SPI_CR1_SPE ((uint16_t)0x0040) /*!< SPI Enable */ +#define SPI_CR1_LSBFIRST ((uint16_t)0x0080) /*!< Frame Format */ +#define SPI_CR1_SSI ((uint16_t)0x0100) /*!< Internal slave select */ +#define SPI_CR1_SSM ((uint16_t)0x0200) /*!< Software slave management */ +#define SPI_CR1_RXONLY ((uint16_t)0x0400) /*!< Receive only */ +#define SPI_CR1_DFF ((uint16_t)0x0800) /*!< Data Frame Format */ +#define SPI_CR1_CRCNEXT ((uint16_t)0x1000) /*!< Transmit CRC next */ +#define SPI_CR1_CRCEN ((uint16_t)0x2000) /*!< Hardware CRC calculation enable */ +#define SPI_CR1_BIDIOE ((uint16_t)0x4000) /*!< Output enable in bidirectional mode */ +#define SPI_CR1_BIDIMODE ((uint16_t)0x8000) /*!< Bidirectional data mode enable */ + +/******************* Bit definition for SPI_CR2 register ********************/ +#define SPI_CR2_RXDMAEN ((uint8_t)0x01) /*!< Rx Buffer DMA Enable */ +#define SPI_CR2_TXDMAEN ((uint8_t)0x02) /*!< Tx Buffer DMA Enable */ +#define SPI_CR2_SSOE ((uint8_t)0x04) /*!< SS Output Enable */ +#define SPI_CR2_ERRIE ((uint8_t)0x20) /*!< Error Interrupt Enable */ +#define SPI_CR2_RXNEIE ((uint8_t)0x40) /*!< RX buffer Not Empty Interrupt Enable */ +#define SPI_CR2_TXEIE ((uint8_t)0x80) /*!< Tx buffer Empty Interrupt Enable */ + +/******************** Bit definition for SPI_SR register ********************/ +#define SPI_SR_RXNE ((uint8_t)0x01) /*!< Receive buffer Not Empty */ +#define SPI_SR_TXE ((uint8_t)0x02) /*!< Transmit buffer Empty */ +#define SPI_SR_CHSIDE ((uint8_t)0x04) /*!< Channel side */ +#define SPI_SR_UDR ((uint8_t)0x08) /*!< Underrun flag */ +#define SPI_SR_CRCERR ((uint8_t)0x10) /*!< CRC Error flag */ +#define SPI_SR_MODF ((uint8_t)0x20) /*!< Mode fault */ +#define SPI_SR_OVR ((uint8_t)0x40) /*!< Overrun flag */ +#define SPI_SR_BSY ((uint8_t)0x80) /*!< Busy flag */ + +/******************** Bit definition for SPI_DR register ********************/ +#define SPI_DR_DR ((uint16_t)0xFFFF) /*!< Data Register */ + +/******************* Bit definition for SPI_CRCPR register ******************/ +#define SPI_CRCPR_CRCPOLY ((uint16_t)0xFFFF) /*!< CRC polynomial register */ + +/****************** Bit definition for SPI_RXCRCR register ******************/ +#define SPI_RXCRCR_RXCRC ((uint16_t)0xFFFF) /*!< Rx CRC Register */ + +/****************** Bit definition for SPI_TXCRCR register ******************/ +#define SPI_TXCRCR_TXCRC ((uint16_t)0xFFFF) /*!< Tx CRC Register */ + +/****************** Bit definition for SPI_I2SCFGR register *****************/ +#define SPI_I2SCFGR_CHLEN ((uint16_t)0x0001) /*!< Channel length (number of bits per audio channel) */ + +#define SPI_I2SCFGR_DATLEN ((uint16_t)0x0006) /*!< DATLEN[1:0] bits (Data length to be transferred) */ +#define SPI_I2SCFGR_DATLEN_0 ((uint16_t)0x0002) /*!< Bit 0 */ +#define SPI_I2SCFGR_DATLEN_1 ((uint16_t)0x0004) /*!< Bit 1 */ + +#define SPI_I2SCFGR_CKPOL ((uint16_t)0x0008) /*!< steady state clock polarity */ + +#define SPI_I2SCFGR_I2SSTD ((uint16_t)0x0030) /*!< I2SSTD[1:0] bits (I2S standard selection) */ +#define SPI_I2SCFGR_I2SSTD_0 ((uint16_t)0x0010) /*!< Bit 0 */ +#define SPI_I2SCFGR_I2SSTD_1 ((uint16_t)0x0020) /*!< Bit 1 */ + +#define SPI_I2SCFGR_PCMSYNC ((uint16_t)0x0080) /*!< PCM frame synchronization */ + +#define SPI_I2SCFGR_I2SCFG ((uint16_t)0x0300) /*!< I2SCFG[1:0] bits (I2S configuration mode) */ +#define SPI_I2SCFGR_I2SCFG_0 ((uint16_t)0x0100) /*!< Bit 0 */ +#define SPI_I2SCFGR_I2SCFG_1 ((uint16_t)0x0200) /*!< Bit 1 */ + +#define SPI_I2SCFGR_I2SE ((uint16_t)0x0400) /*!< I2S Enable */ +#define SPI_I2SCFGR_I2SMOD ((uint16_t)0x0800) /*!< I2S mode selection */ + +/****************** Bit definition for SPI_I2SPR register *******************/ +#define SPI_I2SPR_I2SDIV ((uint16_t)0x00FF) /*!< I2S Linear prescaler */ +#define SPI_I2SPR_ODD ((uint16_t)0x0100) /*!< Odd factor for the prescaler */ +#define SPI_I2SPR_MCKOE ((uint16_t)0x0200) /*!< Master Clock Output Enable */ + +/******************************************************************************/ +/* */ +/* Inter-integrated Circuit Interface */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for I2C_CR1 register ********************/ +#define I2C_CR1_PE ((uint16_t)0x0001) /*!< Peripheral Enable */ +#define I2C_CR1_SMBUS ((uint16_t)0x0002) /*!< SMBus Mode */ +#define I2C_CR1_SMBTYPE ((uint16_t)0x0008) /*!< SMBus Type */ +#define I2C_CR1_ENARP ((uint16_t)0x0010) /*!< ARP Enable */ +#define I2C_CR1_ENPEC ((uint16_t)0x0020) /*!< PEC Enable */ +#define I2C_CR1_ENGC ((uint16_t)0x0040) /*!< General Call Enable */ +#define I2C_CR1_NOSTRETCH ((uint16_t)0x0080) /*!< Clock Stretching Disable (Slave mode) */ +#define I2C_CR1_START ((uint16_t)0x0100) /*!< Start Generation */ +#define I2C_CR1_STOP ((uint16_t)0x0200) /*!< Stop Generation */ +#define I2C_CR1_ACK ((uint16_t)0x0400) /*!< Acknowledge Enable */ +#define I2C_CR1_POS ((uint16_t)0x0800) /*!< Acknowledge/PEC Position (for data reception) */ +#define I2C_CR1_PEC ((uint16_t)0x1000) /*!< Packet Error Checking */ +#define I2C_CR1_ALERT ((uint16_t)0x2000) /*!< SMBus Alert */ +#define I2C_CR1_SWRST ((uint16_t)0x8000) /*!< Software Reset */ + +/******************* Bit definition for I2C_CR2 register ********************/ +#define I2C_CR2_FREQ ((uint16_t)0x003F) /*!< FREQ[5:0] bits (Peripheral Clock Frequency) */ +#define I2C_CR2_FREQ_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define I2C_CR2_FREQ_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define I2C_CR2_FREQ_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define I2C_CR2_FREQ_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define I2C_CR2_FREQ_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define I2C_CR2_FREQ_5 ((uint16_t)0x0020) /*!< Bit 5 */ + +#define I2C_CR2_ITERREN ((uint16_t)0x0100) /*!< Error Interrupt Enable */ +#define I2C_CR2_ITEVTEN ((uint16_t)0x0200) /*!< Event Interrupt Enable */ +#define I2C_CR2_ITBUFEN ((uint16_t)0x0400) /*!< Buffer Interrupt Enable */ +#define I2C_CR2_DMAEN ((uint16_t)0x0800) /*!< DMA Requests Enable */ +#define I2C_CR2_LAST ((uint16_t)0x1000) /*!< DMA Last Transfer */ + +/******************* Bit definition for I2C_OAR1 register *******************/ +#define I2C_OAR1_ADD1_7 ((uint16_t)0x00FE) /*!< Interface Address */ +#define I2C_OAR1_ADD8_9 ((uint16_t)0x0300) /*!< Interface Address */ + +#define I2C_OAR1_ADD0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define I2C_OAR1_ADD1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define I2C_OAR1_ADD2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define I2C_OAR1_ADD3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define I2C_OAR1_ADD4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define I2C_OAR1_ADD5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define I2C_OAR1_ADD6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define I2C_OAR1_ADD7 ((uint16_t)0x0080) /*!< Bit 7 */ +#define I2C_OAR1_ADD8 ((uint16_t)0x0100) /*!< Bit 8 */ +#define I2C_OAR1_ADD9 ((uint16_t)0x0200) /*!< Bit 9 */ + +#define I2C_OAR1_ADDMODE ((uint16_t)0x8000) /*!< Addressing Mode (Slave mode) */ + +/******************* Bit definition for I2C_OAR2 register *******************/ +#define I2C_OAR2_ENDUAL ((uint8_t)0x01) /*!< Dual addressing mode enable */ +#define I2C_OAR2_ADD2 ((uint8_t)0xFE) /*!< Interface address */ + +/******************** Bit definition for I2C_DR register ********************/ +#define I2C_DR_DR ((uint8_t)0xFF) /*!< 8-bit Data Register */ + +/******************* Bit definition for I2C_SR1 register ********************/ +#define I2C_SR1_SB ((uint16_t)0x0001) /*!< Start Bit (Master mode) */ +#define I2C_SR1_ADDR ((uint16_t)0x0002) /*!< Address sent (master mode)/matched (slave mode) */ +#define I2C_SR1_BTF ((uint16_t)0x0004) /*!< Byte Transfer Finished */ +#define I2C_SR1_ADD10 ((uint16_t)0x0008) /*!< 10-bit header sent (Master mode) */ +#define I2C_SR1_STOPF ((uint16_t)0x0010) /*!< Stop detection (Slave mode) */ +#define I2C_SR1_RXNE ((uint16_t)0x0040) /*!< Data Register not Empty (receivers) */ +#define I2C_SR1_TXE ((uint16_t)0x0080) /*!< Data Register Empty (transmitters) */ +#define I2C_SR1_BERR ((uint16_t)0x0100) /*!< Bus Error */ +#define I2C_SR1_ARLO ((uint16_t)0x0200) /*!< Arbitration Lost (master mode) */ +#define I2C_SR1_AF ((uint16_t)0x0400) /*!< Acknowledge Failure */ +#define I2C_SR1_OVR ((uint16_t)0x0800) /*!< Overrun/Underrun */ +#define I2C_SR1_PECERR ((uint16_t)0x1000) /*!< PEC Error in reception */ +#define I2C_SR1_TIMEOUT ((uint16_t)0x4000) /*!< Timeout or Tlow Error */ +#define I2C_SR1_SMBALERT ((uint16_t)0x8000) /*!< SMBus Alert */ + +/******************* Bit definition for I2C_SR2 register ********************/ +#define I2C_SR2_MSL ((uint16_t)0x0001) /*!< Master/Slave */ +#define I2C_SR2_BUSY ((uint16_t)0x0002) /*!< Bus Busy */ +#define I2C_SR2_TRA ((uint16_t)0x0004) /*!< Transmitter/Receiver */ +#define I2C_SR2_GENCALL ((uint16_t)0x0010) /*!< General Call Address (Slave mode) */ +#define I2C_SR2_SMBDEFAULT ((uint16_t)0x0020) /*!< SMBus Device Default Address (Slave mode) */ +#define I2C_SR2_SMBHOST ((uint16_t)0x0040) /*!< SMBus Host Header (Slave mode) */ +#define I2C_SR2_DUALF ((uint16_t)0x0080) /*!< Dual Flag (Slave mode) */ +#define I2C_SR2_PEC ((uint16_t)0xFF00) /*!< Packet Error Checking Register */ + +/******************* Bit definition for I2C_CCR register ********************/ +#define I2C_CCR_CCR ((uint16_t)0x0FFF) /*!< Clock Control Register in Fast/Standard mode (Master mode) */ +#define I2C_CCR_DUTY ((uint16_t)0x4000) /*!< Fast Mode Duty Cycle */ +#define I2C_CCR_FS ((uint16_t)0x8000) /*!< I2C Master Mode Selection */ + +/****************** Bit definition for I2C_TRISE register *******************/ +#define I2C_TRISE_TRISE ((uint8_t)0x3F) /*!< Maximum Rise Time in Fast/Standard mode (Master mode) */ + +/******************************************************************************/ +/* */ +/* Universal Synchronous Asynchronous Receiver Transmitter */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for USART_SR register *******************/ +#define USART_SR_PE ((uint16_t)0x0001) /*!< Parity Error */ +#define USART_SR_FE ((uint16_t)0x0002) /*!< Framing Error */ +#define USART_SR_NE ((uint16_t)0x0004) /*!< Noise Error Flag */ +#define USART_SR_ORE ((uint16_t)0x0008) /*!< OverRun Error */ +#define USART_SR_IDLE ((uint16_t)0x0010) /*!< IDLE line detected */ +#define USART_SR_RXNE ((uint16_t)0x0020) /*!< Read Data Register Not Empty */ +#define USART_SR_TC ((uint16_t)0x0040) /*!< Transmission Complete */ +#define USART_SR_TXE ((uint16_t)0x0080) /*!< Transmit Data Register Empty */ +#define USART_SR_LBD ((uint16_t)0x0100) /*!< LIN Break Detection Flag */ +#define USART_SR_CTS ((uint16_t)0x0200) /*!< CTS Flag */ + +/******************* Bit definition for USART_DR register *******************/ +#define USART_DR_DR ((uint16_t)0x01FF) /*!< Data value */ + +/****************** Bit definition for USART_BRR register *******************/ +#define USART_BRR_DIV_Fraction ((uint16_t)0x000F) /*!< Fraction of USARTDIV */ +#define USART_BRR_DIV_Mantissa ((uint16_t)0xFFF0) /*!< Mantissa of USARTDIV */ + +/****************** Bit definition for USART_CR1 register *******************/ +#define USART_CR1_SBK ((uint16_t)0x0001) /*!< Send Break */ +#define USART_CR1_RWU ((uint16_t)0x0002) /*!< Receiver wakeup */ +#define USART_CR1_RE ((uint16_t)0x0004) /*!< Receiver Enable */ +#define USART_CR1_TE ((uint16_t)0x0008) /*!< Transmitter Enable */ +#define USART_CR1_IDLEIE ((uint16_t)0x0010) /*!< IDLE Interrupt Enable */ +#define USART_CR1_RXNEIE ((uint16_t)0x0020) /*!< RXNE Interrupt Enable */ +#define USART_CR1_TCIE ((uint16_t)0x0040) /*!< Transmission Complete Interrupt Enable */ +#define USART_CR1_TXEIE ((uint16_t)0x0080) /*!< PE Interrupt Enable */ +#define USART_CR1_PEIE ((uint16_t)0x0100) /*!< PE Interrupt Enable */ +#define USART_CR1_PS ((uint16_t)0x0200) /*!< Parity Selection */ +#define USART_CR1_PCE ((uint16_t)0x0400) /*!< Parity Control Enable */ +#define USART_CR1_WAKE ((uint16_t)0x0800) /*!< Wakeup method */ +#define USART_CR1_M ((uint16_t)0x1000) /*!< Word length */ +#define USART_CR1_UE ((uint16_t)0x2000) /*!< USART Enable */ +#define USART_CR1_OVER8 ((uint16_t)0x8000) /*!< USART Oversmapling 8-bits */ + +/****************** Bit definition for USART_CR2 register *******************/ +#define USART_CR2_ADD ((uint16_t)0x000F) /*!< Address of the USART node */ +#define USART_CR2_LBDL ((uint16_t)0x0020) /*!< LIN Break Detection Length */ +#define USART_CR2_LBDIE ((uint16_t)0x0040) /*!< LIN Break Detection Interrupt Enable */ +#define USART_CR2_LBCL ((uint16_t)0x0100) /*!< Last Bit Clock pulse */ +#define USART_CR2_CPHA ((uint16_t)0x0200) /*!< Clock Phase */ +#define USART_CR2_CPOL ((uint16_t)0x0400) /*!< Clock Polarity */ +#define USART_CR2_CLKEN ((uint16_t)0x0800) /*!< Clock Enable */ + +#define USART_CR2_STOP ((uint16_t)0x3000) /*!< STOP[1:0] bits (STOP bits) */ +#define USART_CR2_STOP_0 ((uint16_t)0x1000) /*!< Bit 0 */ +#define USART_CR2_STOP_1 ((uint16_t)0x2000) /*!< Bit 1 */ + +#define USART_CR2_LINEN ((uint16_t)0x4000) /*!< LIN mode enable */ + +/****************** Bit definition for USART_CR3 register *******************/ +#define USART_CR3_EIE ((uint16_t)0x0001) /*!< Error Interrupt Enable */ +#define USART_CR3_IREN ((uint16_t)0x0002) /*!< IrDA mode Enable */ +#define USART_CR3_IRLP ((uint16_t)0x0004) /*!< IrDA Low-Power */ +#define USART_CR3_HDSEL ((uint16_t)0x0008) /*!< Half-Duplex Selection */ +#define USART_CR3_NACK ((uint16_t)0x0010) /*!< Smartcard NACK enable */ +#define USART_CR3_SCEN ((uint16_t)0x0020) /*!< Smartcard mode enable */ +#define USART_CR3_DMAR ((uint16_t)0x0040) /*!< DMA Enable Receiver */ +#define USART_CR3_DMAT ((uint16_t)0x0080) /*!< DMA Enable Transmitter */ +#define USART_CR3_RTSE ((uint16_t)0x0100) /*!< RTS Enable */ +#define USART_CR3_CTSE ((uint16_t)0x0200) /*!< CTS Enable */ +#define USART_CR3_CTSIE ((uint16_t)0x0400) /*!< CTS Interrupt Enable */ +#define USART_CR3_ONEBIT ((uint16_t)0x0800) /*!< One Bit method */ + +/****************** Bit definition for USART_GTPR register ******************/ +#define USART_GTPR_PSC ((uint16_t)0x00FF) /*!< PSC[7:0] bits (Prescaler value) */ +#define USART_GTPR_PSC_0 ((uint16_t)0x0001) /*!< Bit 0 */ +#define USART_GTPR_PSC_1 ((uint16_t)0x0002) /*!< Bit 1 */ +#define USART_GTPR_PSC_2 ((uint16_t)0x0004) /*!< Bit 2 */ +#define USART_GTPR_PSC_3 ((uint16_t)0x0008) /*!< Bit 3 */ +#define USART_GTPR_PSC_4 ((uint16_t)0x0010) /*!< Bit 4 */ +#define USART_GTPR_PSC_5 ((uint16_t)0x0020) /*!< Bit 5 */ +#define USART_GTPR_PSC_6 ((uint16_t)0x0040) /*!< Bit 6 */ +#define USART_GTPR_PSC_7 ((uint16_t)0x0080) /*!< Bit 7 */ + +#define USART_GTPR_GT ((uint16_t)0xFF00) /*!< Guard time value */ + +/******************************************************************************/ +/* */ +/* Debug MCU */ +/* */ +/******************************************************************************/ + +/**************** Bit definition for DBGMCU_IDCODE register *****************/ +#define DBGMCU_IDCODE_DEV_ID ((uint32_t)0x00000FFF) /*!< Device Identifier */ + +#define DBGMCU_IDCODE_REV_ID ((uint32_t)0xFFFF0000) /*!< REV_ID[15:0] bits (Revision Identifier) */ +#define DBGMCU_IDCODE_REV_ID_0 ((uint32_t)0x00010000) /*!< Bit 0 */ +#define DBGMCU_IDCODE_REV_ID_1 ((uint32_t)0x00020000) /*!< Bit 1 */ +#define DBGMCU_IDCODE_REV_ID_2 ((uint32_t)0x00040000) /*!< Bit 2 */ +#define DBGMCU_IDCODE_REV_ID_3 ((uint32_t)0x00080000) /*!< Bit 3 */ +#define DBGMCU_IDCODE_REV_ID_4 ((uint32_t)0x00100000) /*!< Bit 4 */ +#define DBGMCU_IDCODE_REV_ID_5 ((uint32_t)0x00200000) /*!< Bit 5 */ +#define DBGMCU_IDCODE_REV_ID_6 ((uint32_t)0x00400000) /*!< Bit 6 */ +#define DBGMCU_IDCODE_REV_ID_7 ((uint32_t)0x00800000) /*!< Bit 7 */ +#define DBGMCU_IDCODE_REV_ID_8 ((uint32_t)0x01000000) /*!< Bit 8 */ +#define DBGMCU_IDCODE_REV_ID_9 ((uint32_t)0x02000000) /*!< Bit 9 */ +#define DBGMCU_IDCODE_REV_ID_10 ((uint32_t)0x04000000) /*!< Bit 10 */ +#define DBGMCU_IDCODE_REV_ID_11 ((uint32_t)0x08000000) /*!< Bit 11 */ +#define DBGMCU_IDCODE_REV_ID_12 ((uint32_t)0x10000000) /*!< Bit 12 */ +#define DBGMCU_IDCODE_REV_ID_13 ((uint32_t)0x20000000) /*!< Bit 13 */ +#define DBGMCU_IDCODE_REV_ID_14 ((uint32_t)0x40000000) /*!< Bit 14 */ +#define DBGMCU_IDCODE_REV_ID_15 ((uint32_t)0x80000000) /*!< Bit 15 */ + +/****************** Bit definition for DBGMCU_CR register *******************/ +#define DBGMCU_CR_DBG_SLEEP ((uint32_t)0x00000001) /*!< Debug Sleep Mode */ +#define DBGMCU_CR_DBG_STOP ((uint32_t)0x00000002) /*!< Debug Stop Mode */ +#define DBGMCU_CR_DBG_STANDBY ((uint32_t)0x00000004) /*!< Debug Standby mode */ +#define DBGMCU_CR_TRACE_IOEN ((uint32_t)0x00000020) /*!< Trace Pin Assignment Control */ + +#define DBGMCU_CR_TRACE_MODE ((uint32_t)0x000000C0) /*!< TRACE_MODE[1:0] bits (Trace Pin Assignment Control) */ +#define DBGMCU_CR_TRACE_MODE_0 ((uint32_t)0x00000040) /*!< Bit 0 */ +#define DBGMCU_CR_TRACE_MODE_1 ((uint32_t)0x00000080) /*!< Bit 1 */ + +#define DBGMCU_CR_DBG_IWDG_STOP ((uint32_t)0x00000100) /*!< Debug Independent Watchdog stopped when Core is halted */ +#define DBGMCU_CR_DBG_WWDG_STOP ((uint32_t)0x00000200) /*!< Debug Window Watchdog stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM1_STOP ((uint32_t)0x00000400) /*!< TIM1 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM2_STOP ((uint32_t)0x00000800) /*!< TIM2 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM3_STOP ((uint32_t)0x00001000) /*!< TIM3 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM4_STOP ((uint32_t)0x00002000) /*!< TIM4 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_CAN1_STOP ((uint32_t)0x00004000) /*!< Debug CAN1 stopped when Core is halted */ +#define DBGMCU_CR_DBG_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) /*!< SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_CR_DBG_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) /*!< SMBUS timeout mode stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM8_STOP ((uint32_t)0x00020000) /*!< TIM8 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM5_STOP ((uint32_t)0x00040000) /*!< TIM5 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM6_STOP ((uint32_t)0x00080000) /*!< TIM6 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_TIM7_STOP ((uint32_t)0x00100000) /*!< TIM7 counter stopped when core is halted */ +#define DBGMCU_CR_DBG_CAN2_STOP ((uint32_t)0x00200000) /*!< Debug CAN2 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM15_STOP ((uint32_t)0x00400000) /*!< Debug TIM15 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM16_STOP ((uint32_t)0x00800000) /*!< Debug TIM16 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM17_STOP ((uint32_t)0x01000000) /*!< Debug TIM17 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM12_STOP ((uint32_t)0x02000000) /*!< Debug TIM12 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM13_STOP ((uint32_t)0x04000000) /*!< Debug TIM13 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM14_STOP ((uint32_t)0x08000000) /*!< Debug TIM14 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM9_STOP ((uint32_t)0x10000000) /*!< Debug TIM9 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM10_STOP ((uint32_t)0x20000000) /*!< Debug TIM10 stopped when Core is halted */ +#define DBGMCU_CR_DBG_TIM11_STOP ((uint32_t)0x40000000) /*!< Debug TIM11 stopped when Core is halted */ + +/******************************************************************************/ +/* */ +/* FLASH and Option Bytes Registers */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for FLASH_ACR register ******************/ +#define FLASH_ACR_LATENCY ((uint8_t)0x03) /*!< LATENCY[2:0] bits (Latency) */ +#define FLASH_ACR_LATENCY_0 ((uint8_t)0x00) /*!< Bit 0 */ +#define FLASH_ACR_LATENCY_1 ((uint8_t)0x01) /*!< Bit 0 */ +#define FLASH_ACR_LATENCY_2 ((uint8_t)0x02) /*!< Bit 1 */ + +#define FLASH_ACR_HLFCYA ((uint8_t)0x08) /*!< Flash Half Cycle Access Enable */ +#define FLASH_ACR_PRFTBE ((uint8_t)0x10) /*!< Prefetch Buffer Enable */ +#define FLASH_ACR_PRFTBS ((uint8_t)0x20) /*!< Prefetch Buffer Status */ + +/****************** Bit definition for FLASH_KEYR register ******************/ +#define FLASH_KEYR_FKEYR ((uint32_t)0xFFFFFFFF) /*!< FPEC Key */ + +/***************** Bit definition for FLASH_OPTKEYR register ****************/ +#define FLASH_OPTKEYR_OPTKEYR ((uint32_t)0xFFFFFFFF) /*!< Option Byte Key */ + +/****************** Bit definition for FLASH_SR register *******************/ +#define FLASH_SR_BSY ((uint8_t)0x01) /*!< Busy */ +#define FLASH_SR_PGERR ((uint8_t)0x04) /*!< Programming Error */ +#define FLASH_SR_WRPRTERR ((uint8_t)0x10) /*!< Write Protection Error */ +#define FLASH_SR_EOP ((uint8_t)0x20) /*!< End of operation */ + +/******************* Bit definition for FLASH_CR register *******************/ +#define FLASH_CR_PG ((uint16_t)0x0001) /*!< Programming */ +#define FLASH_CR_PER ((uint16_t)0x0002) /*!< Page Erase */ +#define FLASH_CR_MER ((uint16_t)0x0004) /*!< Mass Erase */ +#define FLASH_CR_OPTPG ((uint16_t)0x0010) /*!< Option Byte Programming */ +#define FLASH_CR_OPTER ((uint16_t)0x0020) /*!< Option Byte Erase */ +#define FLASH_CR_STRT ((uint16_t)0x0040) /*!< Start */ +#define FLASH_CR_LOCK ((uint16_t)0x0080) /*!< Lock */ +#define FLASH_CR_OPTWRE ((uint16_t)0x0200) /*!< Option Bytes Write Enable */ +#define FLASH_CR_ERRIE ((uint16_t)0x0400) /*!< Error Interrupt Enable */ +#define FLASH_CR_EOPIE ((uint16_t)0x1000) /*!< End of operation interrupt enable */ + +/******************* Bit definition for FLASH_AR register *******************/ +#define FLASH_AR_FAR ((uint32_t)0xFFFFFFFF) /*!< Flash Address */ + +/****************** Bit definition for FLASH_OBR register *******************/ +#define FLASH_OBR_OPTERR ((uint16_t)0x0001) /*!< Option Byte Error */ +#define FLASH_OBR_RDPRT ((uint16_t)0x0002) /*!< Read protection */ + +#define FLASH_OBR_USER ((uint16_t)0x03FC) /*!< User Option Bytes */ +#define FLASH_OBR_WDG_SW ((uint16_t)0x0004) /*!< WDG_SW */ +#define FLASH_OBR_nRST_STOP ((uint16_t)0x0008) /*!< nRST_STOP */ +#define FLASH_OBR_nRST_STDBY ((uint16_t)0x0010) /*!< nRST_STDBY */ +#define FLASH_OBR_BFB2 ((uint16_t)0x0020) /*!< BFB2 */ + +/****************** Bit definition for FLASH_WRPR register ******************/ +#define FLASH_WRPR_WRP ((uint32_t)0xFFFFFFFF) /*!< Write Protect */ + +/*----------------------------------------------------------------------------*/ + +/****************** Bit definition for FLASH_RDP register *******************/ +#define FLASH_RDP_RDP ((uint32_t)0x000000FF) /*!< Read protection option byte */ +#define FLASH_RDP_nRDP ((uint32_t)0x0000FF00) /*!< Read protection complemented option byte */ + +/****************** Bit definition for FLASH_USER register ******************/ +#define FLASH_USER_USER ((uint32_t)0x00FF0000) /*!< User option byte */ +#define FLASH_USER_nUSER ((uint32_t)0xFF000000) /*!< User complemented option byte */ + +/****************** Bit definition for FLASH_Data0 register *****************/ +#define FLASH_Data0_Data0 ((uint32_t)0x000000FF) /*!< User data storage option byte */ +#define FLASH_Data0_nData0 ((uint32_t)0x0000FF00) /*!< User data storage complemented option byte */ + +/****************** Bit definition for FLASH_Data1 register *****************/ +#define FLASH_Data1_Data1 ((uint32_t)0x00FF0000) /*!< User data storage option byte */ +#define FLASH_Data1_nData1 ((uint32_t)0xFF000000) /*!< User data storage complemented option byte */ + +/****************** Bit definition for FLASH_WRP0 register ******************/ +#define FLASH_WRP0_WRP0 ((uint32_t)0x000000FF) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP0_nWRP0 ((uint32_t)0x0000FF00) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP1 register ******************/ +#define FLASH_WRP1_WRP1 ((uint32_t)0x00FF0000) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP1_nWRP1 ((uint32_t)0xFF000000) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP2 register ******************/ +#define FLASH_WRP2_WRP2 ((uint32_t)0x000000FF) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP2_nWRP2 ((uint32_t)0x0000FF00) /*!< Flash memory write protection complemented option bytes */ + +/****************** Bit definition for FLASH_WRP3 register ******************/ +#define FLASH_WRP3_WRP3 ((uint32_t)0x00FF0000) /*!< Flash memory write protection option bytes */ +#define FLASH_WRP3_nWRP3 ((uint32_t)0xFF000000) /*!< Flash memory write protection complemented option bytes */ + +#ifdef STM32F10X_CL +/******************************************************************************/ +/* Ethernet MAC Registers bits definitions */ +/******************************************************************************/ +/* Bit definition for Ethernet MAC Control Register register */ +#define ETH_MACCR_WD ((uint32_t)0x00800000) /* Watchdog disable */ +#define ETH_MACCR_JD ((uint32_t)0x00400000) /* Jabber disable */ +#define ETH_MACCR_IFG ((uint32_t)0x000E0000) /* Inter-frame gap */ + #define ETH_MACCR_IFG_96Bit ((uint32_t)0x00000000) /* Minimum IFG between frames during transmission is 96Bit */ + #define ETH_MACCR_IFG_88Bit ((uint32_t)0x00020000) /* Minimum IFG between frames during transmission is 88Bit */ + #define ETH_MACCR_IFG_80Bit ((uint32_t)0x00040000) /* Minimum IFG between frames during transmission is 80Bit */ + #define ETH_MACCR_IFG_72Bit ((uint32_t)0x00060000) /* Minimum IFG between frames during transmission is 72Bit */ + #define ETH_MACCR_IFG_64Bit ((uint32_t)0x00080000) /* Minimum IFG between frames during transmission is 64Bit */ + #define ETH_MACCR_IFG_56Bit ((uint32_t)0x000A0000) /* Minimum IFG between frames during transmission is 56Bit */ + #define ETH_MACCR_IFG_48Bit ((uint32_t)0x000C0000) /* Minimum IFG between frames during transmission is 48Bit */ + #define ETH_MACCR_IFG_40Bit ((uint32_t)0x000E0000) /* Minimum IFG between frames during transmission is 40Bit */ +#define ETH_MACCR_CSD ((uint32_t)0x00010000) /* Carrier sense disable (during transmission) */ +#define ETH_MACCR_FES ((uint32_t)0x00004000) /* Fast ethernet speed */ +#define ETH_MACCR_ROD ((uint32_t)0x00002000) /* Receive own disable */ +#define ETH_MACCR_LM ((uint32_t)0x00001000) /* loopback mode */ +#define ETH_MACCR_DM ((uint32_t)0x00000800) /* Duplex mode */ +#define ETH_MACCR_IPCO ((uint32_t)0x00000400) /* IP Checksum offload */ +#define ETH_MACCR_RD ((uint32_t)0x00000200) /* Retry disable */ +#define ETH_MACCR_APCS ((uint32_t)0x00000080) /* Automatic Pad/CRC stripping */ +#define ETH_MACCR_BL ((uint32_t)0x00000060) /* Back-off limit: random integer number (r) of slot time delays before rescheduling + a transmission attempt during retries after a collision: 0 =< r <2^k */ + #define ETH_MACCR_BL_10 ((uint32_t)0x00000000) /* k = min (n, 10) */ + #define ETH_MACCR_BL_8 ((uint32_t)0x00000020) /* k = min (n, 8) */ + #define ETH_MACCR_BL_4 ((uint32_t)0x00000040) /* k = min (n, 4) */ + #define ETH_MACCR_BL_1 ((uint32_t)0x00000060) /* k = min (n, 1) */ +#define ETH_MACCR_DC ((uint32_t)0x00000010) /* Defferal check */ +#define ETH_MACCR_TE ((uint32_t)0x00000008) /* Transmitter enable */ +#define ETH_MACCR_RE ((uint32_t)0x00000004) /* Receiver enable */ + +/* Bit definition for Ethernet MAC Frame Filter Register */ +#define ETH_MACFFR_RA ((uint32_t)0x80000000) /* Receive all */ +#define ETH_MACFFR_HPF ((uint32_t)0x00000400) /* Hash or perfect filter */ +#define ETH_MACFFR_SAF ((uint32_t)0x00000200) /* Source address filter enable */ +#define ETH_MACFFR_SAIF ((uint32_t)0x00000100) /* SA inverse filtering */ +#define ETH_MACFFR_PCF ((uint32_t)0x000000C0) /* Pass control frames: 3 cases */ + #define ETH_MACFFR_PCF_BlockAll ((uint32_t)0x00000040) /* MAC filters all control frames from reaching the application */ + #define ETH_MACFFR_PCF_ForwardAll ((uint32_t)0x00000080) /* MAC forwards all control frames to application even if they fail the Address Filter */ + #define ETH_MACFFR_PCF_ForwardPassedAddrFilter ((uint32_t)0x000000C0) /* MAC forwards control frames that pass the Address Filter. */ +#define ETH_MACFFR_BFD ((uint32_t)0x00000020) /* Broadcast frame disable */ +#define ETH_MACFFR_PAM ((uint32_t)0x00000010) /* Pass all mutlicast */ +#define ETH_MACFFR_DAIF ((uint32_t)0x00000008) /* DA Inverse filtering */ +#define ETH_MACFFR_HM ((uint32_t)0x00000004) /* Hash multicast */ +#define ETH_MACFFR_HU ((uint32_t)0x00000002) /* Hash unicast */ +#define ETH_MACFFR_PM ((uint32_t)0x00000001) /* Promiscuous mode */ + +/* Bit definition for Ethernet MAC Hash Table High Register */ +#define ETH_MACHTHR_HTH ((uint32_t)0xFFFFFFFF) /* Hash table high */ + +/* Bit definition for Ethernet MAC Hash Table Low Register */ +#define ETH_MACHTLR_HTL ((uint32_t)0xFFFFFFFF) /* Hash table low */ + +/* Bit definition for Ethernet MAC MII Address Register */ +#define ETH_MACMIIAR_PA ((uint32_t)0x0000F800) /* Physical layer address */ +#define ETH_MACMIIAR_MR ((uint32_t)0x000007C0) /* MII register in the selected PHY */ +#define ETH_MACMIIAR_CR ((uint32_t)0x0000001C) /* CR clock range: 6 cases */ + #define ETH_MACMIIAR_CR_Div42 ((uint32_t)0x00000000) /* HCLK:60-72 MHz; MDC clock= HCLK/42 */ + #define ETH_MACMIIAR_CR_Div16 ((uint32_t)0x00000008) /* HCLK:20-35 MHz; MDC clock= HCLK/16 */ + #define ETH_MACMIIAR_CR_Div26 ((uint32_t)0x0000000C) /* HCLK:35-60 MHz; MDC clock= HCLK/26 */ +#define ETH_MACMIIAR_MW ((uint32_t)0x00000002) /* MII write */ +#define ETH_MACMIIAR_MB ((uint32_t)0x00000001) /* MII busy */ + +/* Bit definition for Ethernet MAC MII Data Register */ +#define ETH_MACMIIDR_MD ((uint32_t)0x0000FFFF) /* MII data: read/write data from/to PHY */ + +/* Bit definition for Ethernet MAC Flow Control Register */ +#define ETH_MACFCR_PT ((uint32_t)0xFFFF0000) /* Pause time */ +#define ETH_MACFCR_ZQPD ((uint32_t)0x00000080) /* Zero-quanta pause disable */ +#define ETH_MACFCR_PLT ((uint32_t)0x00000030) /* Pause low threshold: 4 cases */ + #define ETH_MACFCR_PLT_Minus4 ((uint32_t)0x00000000) /* Pause time minus 4 slot times */ + #define ETH_MACFCR_PLT_Minus28 ((uint32_t)0x00000010) /* Pause time minus 28 slot times */ + #define ETH_MACFCR_PLT_Minus144 ((uint32_t)0x00000020) /* Pause time minus 144 slot times */ + #define ETH_MACFCR_PLT_Minus256 ((uint32_t)0x00000030) /* Pause time minus 256 slot times */ +#define ETH_MACFCR_UPFD ((uint32_t)0x00000008) /* Unicast pause frame detect */ +#define ETH_MACFCR_RFCE ((uint32_t)0x00000004) /* Receive flow control enable */ +#define ETH_MACFCR_TFCE ((uint32_t)0x00000002) /* Transmit flow control enable */ +#define ETH_MACFCR_FCBBPA ((uint32_t)0x00000001) /* Flow control busy/backpressure activate */ + +/* Bit definition for Ethernet MAC VLAN Tag Register */ +#define ETH_MACVLANTR_VLANTC ((uint32_t)0x00010000) /* 12-bit VLAN tag comparison */ +#define ETH_MACVLANTR_VLANTI ((uint32_t)0x0000FFFF) /* VLAN tag identifier (for receive frames) */ + +/* Bit definition for Ethernet MAC Remote Wake-UpFrame Filter Register */ +#define ETH_MACRWUFFR_D ((uint32_t)0xFFFFFFFF) /* Wake-up frame filter register data */ +/* Eight sequential Writes to this address (offset 0x28) will write all Wake-UpFrame Filter Registers. + Eight sequential Reads from this address (offset 0x28) will read all Wake-UpFrame Filter Registers. */ +/* Wake-UpFrame Filter Reg0 : Filter 0 Byte Mask + Wake-UpFrame Filter Reg1 : Filter 1 Byte Mask + Wake-UpFrame Filter Reg2 : Filter 2 Byte Mask + Wake-UpFrame Filter Reg3 : Filter 3 Byte Mask + Wake-UpFrame Filter Reg4 : RSVD - Filter3 Command - RSVD - Filter2 Command - + RSVD - Filter1 Command - RSVD - Filter0 Command + Wake-UpFrame Filter Re5 : Filter3 Offset - Filter2 Offset - Filter1 Offset - Filter0 Offset + Wake-UpFrame Filter Re6 : Filter1 CRC16 - Filter0 CRC16 + Wake-UpFrame Filter Re7 : Filter3 CRC16 - Filter2 CRC16 */ + +/* Bit definition for Ethernet MAC PMT Control and Status Register */ +#define ETH_MACPMTCSR_WFFRPR ((uint32_t)0x80000000) /* Wake-Up Frame Filter Register Pointer Reset */ +#define ETH_MACPMTCSR_GU ((uint32_t)0x00000200) /* Global Unicast */ +#define ETH_MACPMTCSR_WFR ((uint32_t)0x00000040) /* Wake-Up Frame Received */ +#define ETH_MACPMTCSR_MPR ((uint32_t)0x00000020) /* Magic Packet Received */ +#define ETH_MACPMTCSR_WFE ((uint32_t)0x00000004) /* Wake-Up Frame Enable */ +#define ETH_MACPMTCSR_MPE ((uint32_t)0x00000002) /* Magic Packet Enable */ +#define ETH_MACPMTCSR_PD ((uint32_t)0x00000001) /* Power Down */ + +/* Bit definition for Ethernet MAC Status Register */ +#define ETH_MACSR_TSTS ((uint32_t)0x00000200) /* Time stamp trigger status */ +#define ETH_MACSR_MMCTS ((uint32_t)0x00000040) /* MMC transmit status */ +#define ETH_MACSR_MMMCRS ((uint32_t)0x00000020) /* MMC receive status */ +#define ETH_MACSR_MMCS ((uint32_t)0x00000010) /* MMC status */ +#define ETH_MACSR_PMTS ((uint32_t)0x00000008) /* PMT status */ + +/* Bit definition for Ethernet MAC Interrupt Mask Register */ +#define ETH_MACIMR_TSTIM ((uint32_t)0x00000200) /* Time stamp trigger interrupt mask */ +#define ETH_MACIMR_PMTIM ((uint32_t)0x00000008) /* PMT interrupt mask */ + +/* Bit definition for Ethernet MAC Address0 High Register */ +#define ETH_MACA0HR_MACA0H ((uint32_t)0x0000FFFF) /* MAC address0 high */ + +/* Bit definition for Ethernet MAC Address0 Low Register */ +#define ETH_MACA0LR_MACA0L ((uint32_t)0xFFFFFFFF) /* MAC address0 low */ + +/* Bit definition for Ethernet MAC Address1 High Register */ +#define ETH_MACA1HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA1HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA1HR_MBC ((uint32_t)0x3F000000) /* Mask byte control: bits to mask for comparison of the MAC Address bytes */ + #define ETH_MACA1HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA1HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA1HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA1HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA1HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA1HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [7:0] */ +#define ETH_MACA1HR_MACA1H ((uint32_t)0x0000FFFF) /* MAC address1 high */ + +/* Bit definition for Ethernet MAC Address1 Low Register */ +#define ETH_MACA1LR_MACA1L ((uint32_t)0xFFFFFFFF) /* MAC address1 low */ + +/* Bit definition for Ethernet MAC Address2 High Register */ +#define ETH_MACA2HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA2HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA2HR_MBC ((uint32_t)0x3F000000) /* Mask byte control */ + #define ETH_MACA2HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA2HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA2HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA2HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA2HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA2HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [70] */ +#define ETH_MACA2HR_MACA2H ((uint32_t)0x0000FFFF) /* MAC address1 high */ + +/* Bit definition for Ethernet MAC Address2 Low Register */ +#define ETH_MACA2LR_MACA2L ((uint32_t)0xFFFFFFFF) /* MAC address2 low */ + +/* Bit definition for Ethernet MAC Address3 High Register */ +#define ETH_MACA3HR_AE ((uint32_t)0x80000000) /* Address enable */ +#define ETH_MACA3HR_SA ((uint32_t)0x40000000) /* Source address */ +#define ETH_MACA3HR_MBC ((uint32_t)0x3F000000) /* Mask byte control */ + #define ETH_MACA3HR_MBC_HBits15_8 ((uint32_t)0x20000000) /* Mask MAC Address high reg bits [15:8] */ + #define ETH_MACA3HR_MBC_HBits7_0 ((uint32_t)0x10000000) /* Mask MAC Address high reg bits [7:0] */ + #define ETH_MACA3HR_MBC_LBits31_24 ((uint32_t)0x08000000) /* Mask MAC Address low reg bits [31:24] */ + #define ETH_MACA3HR_MBC_LBits23_16 ((uint32_t)0x04000000) /* Mask MAC Address low reg bits [23:16] */ + #define ETH_MACA3HR_MBC_LBits15_8 ((uint32_t)0x02000000) /* Mask MAC Address low reg bits [15:8] */ + #define ETH_MACA3HR_MBC_LBits7_0 ((uint32_t)0x01000000) /* Mask MAC Address low reg bits [70] */ +#define ETH_MACA3HR_MACA3H ((uint32_t)0x0000FFFF) /* MAC address3 high */ + +/* Bit definition for Ethernet MAC Address3 Low Register */ +#define ETH_MACA3LR_MACA3L ((uint32_t)0xFFFFFFFF) /* MAC address3 low */ + +/******************************************************************************/ +/* Ethernet MMC Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet MMC Contol Register */ +#define ETH_MMCCR_MCF ((uint32_t)0x00000008) /* MMC Counter Freeze */ +#define ETH_MMCCR_ROR ((uint32_t)0x00000004) /* Reset on Read */ +#define ETH_MMCCR_CSR ((uint32_t)0x00000002) /* Counter Stop Rollover */ +#define ETH_MMCCR_CR ((uint32_t)0x00000001) /* Counters Reset */ + +/* Bit definition for Ethernet MMC Receive Interrupt Register */ +#define ETH_MMCRIR_RGUFS ((uint32_t)0x00020000) /* Set when Rx good unicast frames counter reaches half the maximum value */ +#define ETH_MMCRIR_RFAES ((uint32_t)0x00000040) /* Set when Rx alignment error counter reaches half the maximum value */ +#define ETH_MMCRIR_RFCES ((uint32_t)0x00000020) /* Set when Rx crc error counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmit Interrupt Register */ +#define ETH_MMCTIR_TGFS ((uint32_t)0x00200000) /* Set when Tx good frame count counter reaches half the maximum value */ +#define ETH_MMCTIR_TGFMSCS ((uint32_t)0x00008000) /* Set when Tx good multi col counter reaches half the maximum value */ +#define ETH_MMCTIR_TGFSCS ((uint32_t)0x00004000) /* Set when Tx good single col counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Receive Interrupt Mask Register */ +#define ETH_MMCRIMR_RGUFM ((uint32_t)0x00020000) /* Mask the interrupt when Rx good unicast frames counter reaches half the maximum value */ +#define ETH_MMCRIMR_RFAEM ((uint32_t)0x00000040) /* Mask the interrupt when when Rx alignment error counter reaches half the maximum value */ +#define ETH_MMCRIMR_RFCEM ((uint32_t)0x00000020) /* Mask the interrupt when Rx crc error counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmit Interrupt Mask Register */ +#define ETH_MMCTIMR_TGFM ((uint32_t)0x00200000) /* Mask the interrupt when Tx good frame count counter reaches half the maximum value */ +#define ETH_MMCTIMR_TGFMSCM ((uint32_t)0x00008000) /* Mask the interrupt when Tx good multi col counter reaches half the maximum value */ +#define ETH_MMCTIMR_TGFSCM ((uint32_t)0x00004000) /* Mask the interrupt when Tx good single col counter reaches half the maximum value */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames after Single Collision Counter Register */ +#define ETH_MMCTGFSCCR_TGFSCC ((uint32_t)0xFFFFFFFF) /* Number of successfully transmitted frames after a single collision in Half-duplex mode. */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames after More than a Single Collision Counter Register */ +#define ETH_MMCTGFMSCCR_TGFMSCC ((uint32_t)0xFFFFFFFF) /* Number of successfully transmitted frames after more than a single collision in Half-duplex mode. */ + +/* Bit definition for Ethernet MMC Transmitted Good Frames Counter Register */ +#define ETH_MMCTGFCR_TGFC ((uint32_t)0xFFFFFFFF) /* Number of good frames transmitted. */ + +/* Bit definition for Ethernet MMC Received Frames with CRC Error Counter Register */ +#define ETH_MMCRFCECR_RFCEC ((uint32_t)0xFFFFFFFF) /* Number of frames received with CRC error. */ + +/* Bit definition for Ethernet MMC Received Frames with Alignement Error Counter Register */ +#define ETH_MMCRFAECR_RFAEC ((uint32_t)0xFFFFFFFF) /* Number of frames received with alignment (dribble) error */ + +/* Bit definition for Ethernet MMC Received Good Unicast Frames Counter Register */ +#define ETH_MMCRGUFCR_RGUFC ((uint32_t)0xFFFFFFFF) /* Number of good unicast frames received. */ + +/******************************************************************************/ +/* Ethernet PTP Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet PTP Time Stamp Contol Register */ +#define ETH_PTPTSCR_TSARU ((uint32_t)0x00000020) /* Addend register update */ +#define ETH_PTPTSCR_TSITE ((uint32_t)0x00000010) /* Time stamp interrupt trigger enable */ +#define ETH_PTPTSCR_TSSTU ((uint32_t)0x00000008) /* Time stamp update */ +#define ETH_PTPTSCR_TSSTI ((uint32_t)0x00000004) /* Time stamp initialize */ +#define ETH_PTPTSCR_TSFCU ((uint32_t)0x00000002) /* Time stamp fine or coarse update */ +#define ETH_PTPTSCR_TSE ((uint32_t)0x00000001) /* Time stamp enable */ + +/* Bit definition for Ethernet PTP Sub-Second Increment Register */ +#define ETH_PTPSSIR_STSSI ((uint32_t)0x000000FF) /* System time Sub-second increment value */ + +/* Bit definition for Ethernet PTP Time Stamp High Register */ +#define ETH_PTPTSHR_STS ((uint32_t)0xFFFFFFFF) /* System Time second */ + +/* Bit definition for Ethernet PTP Time Stamp Low Register */ +#define ETH_PTPTSLR_STPNS ((uint32_t)0x80000000) /* System Time Positive or negative time */ +#define ETH_PTPTSLR_STSS ((uint32_t)0x7FFFFFFF) /* System Time sub-seconds */ + +/* Bit definition for Ethernet PTP Time Stamp High Update Register */ +#define ETH_PTPTSHUR_TSUS ((uint32_t)0xFFFFFFFF) /* Time stamp update seconds */ + +/* Bit definition for Ethernet PTP Time Stamp Low Update Register */ +#define ETH_PTPTSLUR_TSUPNS ((uint32_t)0x80000000) /* Time stamp update Positive or negative time */ +#define ETH_PTPTSLUR_TSUSS ((uint32_t)0x7FFFFFFF) /* Time stamp update sub-seconds */ + +/* Bit definition for Ethernet PTP Time Stamp Addend Register */ +#define ETH_PTPTSAR_TSA ((uint32_t)0xFFFFFFFF) /* Time stamp addend */ + +/* Bit definition for Ethernet PTP Target Time High Register */ +#define ETH_PTPTTHR_TTSH ((uint32_t)0xFFFFFFFF) /* Target time stamp high */ + +/* Bit definition for Ethernet PTP Target Time Low Register */ +#define ETH_PTPTTLR_TTSL ((uint32_t)0xFFFFFFFF) /* Target time stamp low */ + +/******************************************************************************/ +/* Ethernet DMA Registers bits definition */ +/******************************************************************************/ + +/* Bit definition for Ethernet DMA Bus Mode Register */ +#define ETH_DMABMR_AAB ((uint32_t)0x02000000) /* Address-Aligned beats */ +#define ETH_DMABMR_FPM ((uint32_t)0x01000000) /* 4xPBL mode */ +#define ETH_DMABMR_USP ((uint32_t)0x00800000) /* Use separate PBL */ +#define ETH_DMABMR_RDP ((uint32_t)0x007E0000) /* RxDMA PBL */ + #define ETH_DMABMR_RDP_1Beat ((uint32_t)0x00020000) /* maximum number of beats to be transferred in one RxDMA transaction is 1 */ + #define ETH_DMABMR_RDP_2Beat ((uint32_t)0x00040000) /* maximum number of beats to be transferred in one RxDMA transaction is 2 */ + #define ETH_DMABMR_RDP_4Beat ((uint32_t)0x00080000) /* maximum number of beats to be transferred in one RxDMA transaction is 4 */ + #define ETH_DMABMR_RDP_8Beat ((uint32_t)0x00100000) /* maximum number of beats to be transferred in one RxDMA transaction is 8 */ + #define ETH_DMABMR_RDP_16Beat ((uint32_t)0x00200000) /* maximum number of beats to be transferred in one RxDMA transaction is 16 */ + #define ETH_DMABMR_RDP_32Beat ((uint32_t)0x00400000) /* maximum number of beats to be transferred in one RxDMA transaction is 32 */ + #define ETH_DMABMR_RDP_4xPBL_4Beat ((uint32_t)0x01020000) /* maximum number of beats to be transferred in one RxDMA transaction is 4 */ + #define ETH_DMABMR_RDP_4xPBL_8Beat ((uint32_t)0x01040000) /* maximum number of beats to be transferred in one RxDMA transaction is 8 */ + #define ETH_DMABMR_RDP_4xPBL_16Beat ((uint32_t)0x01080000) /* maximum number of beats to be transferred in one RxDMA transaction is 16 */ + #define ETH_DMABMR_RDP_4xPBL_32Beat ((uint32_t)0x01100000) /* maximum number of beats to be transferred in one RxDMA transaction is 32 */ + #define ETH_DMABMR_RDP_4xPBL_64Beat ((uint32_t)0x01200000) /* maximum number of beats to be transferred in one RxDMA transaction is 64 */ + #define ETH_DMABMR_RDP_4xPBL_128Beat ((uint32_t)0x01400000) /* maximum number of beats to be transferred in one RxDMA transaction is 128 */ +#define ETH_DMABMR_FB ((uint32_t)0x00010000) /* Fixed Burst */ +#define ETH_DMABMR_RTPR ((uint32_t)0x0000C000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_1_1 ((uint32_t)0x00000000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_2_1 ((uint32_t)0x00004000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_3_1 ((uint32_t)0x00008000) /* Rx Tx priority ratio */ + #define ETH_DMABMR_RTPR_4_1 ((uint32_t)0x0000C000) /* Rx Tx priority ratio */ +#define ETH_DMABMR_PBL ((uint32_t)0x00003F00) /* Programmable burst length */ + #define ETH_DMABMR_PBL_1Beat ((uint32_t)0x00000100) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */ + #define ETH_DMABMR_PBL_2Beat ((uint32_t)0x00000200) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */ + #define ETH_DMABMR_PBL_4Beat ((uint32_t)0x00000400) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ + #define ETH_DMABMR_PBL_8Beat ((uint32_t)0x00000800) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ + #define ETH_DMABMR_PBL_16Beat ((uint32_t)0x00001000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ + #define ETH_DMABMR_PBL_32Beat ((uint32_t)0x00002000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ + #define ETH_DMABMR_PBL_4xPBL_4Beat ((uint32_t)0x01000100) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ + #define ETH_DMABMR_PBL_4xPBL_8Beat ((uint32_t)0x01000200) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ + #define ETH_DMABMR_PBL_4xPBL_16Beat ((uint32_t)0x01000400) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ + #define ETH_DMABMR_PBL_4xPBL_32Beat ((uint32_t)0x01000800) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ + #define ETH_DMABMR_PBL_4xPBL_64Beat ((uint32_t)0x01001000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */ + #define ETH_DMABMR_PBL_4xPBL_128Beat ((uint32_t)0x01002000) /* maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */ +#define ETH_DMABMR_DSL ((uint32_t)0x0000007C) /* Descriptor Skip Length */ +#define ETH_DMABMR_DA ((uint32_t)0x00000002) /* DMA arbitration scheme */ +#define ETH_DMABMR_SR ((uint32_t)0x00000001) /* Software reset */ + +/* Bit definition for Ethernet DMA Transmit Poll Demand Register */ +#define ETH_DMATPDR_TPD ((uint32_t)0xFFFFFFFF) /* Transmit poll demand */ + +/* Bit definition for Ethernet DMA Receive Poll Demand Register */ +#define ETH_DMARPDR_RPD ((uint32_t)0xFFFFFFFF) /* Receive poll demand */ + +/* Bit definition for Ethernet DMA Receive Descriptor List Address Register */ +#define ETH_DMARDLAR_SRL ((uint32_t)0xFFFFFFFF) /* Start of receive list */ + +/* Bit definition for Ethernet DMA Transmit Descriptor List Address Register */ +#define ETH_DMATDLAR_STL ((uint32_t)0xFFFFFFFF) /* Start of transmit list */ + +/* Bit definition for Ethernet DMA Status Register */ +#define ETH_DMASR_TSTS ((uint32_t)0x20000000) /* Time-stamp trigger status */ +#define ETH_DMASR_PMTS ((uint32_t)0x10000000) /* PMT status */ +#define ETH_DMASR_MMCS ((uint32_t)0x08000000) /* MMC status */ +#define ETH_DMASR_EBS ((uint32_t)0x03800000) /* Error bits status */ + /* combination with EBS[2:0] for GetFlagStatus function */ + #define ETH_DMASR_EBS_DescAccess ((uint32_t)0x02000000) /* Error bits 0-data buffer, 1-desc. access */ + #define ETH_DMASR_EBS_ReadTransf ((uint32_t)0x01000000) /* Error bits 0-write trnsf, 1-read transfr */ + #define ETH_DMASR_EBS_DataTransfTx ((uint32_t)0x00800000) /* Error bits 0-Rx DMA, 1-Tx DMA */ +#define ETH_DMASR_TPS ((uint32_t)0x00700000) /* Transmit process state */ + #define ETH_DMASR_TPS_Stopped ((uint32_t)0x00000000) /* Stopped - Reset or Stop Tx Command issued */ + #define ETH_DMASR_TPS_Fetching ((uint32_t)0x00100000) /* Running - fetching the Tx descriptor */ + #define ETH_DMASR_TPS_Waiting ((uint32_t)0x00200000) /* Running - waiting for status */ + #define ETH_DMASR_TPS_Reading ((uint32_t)0x00300000) /* Running - reading the data from host memory */ + #define ETH_DMASR_TPS_Suspended ((uint32_t)0x00600000) /* Suspended - Tx Descriptor unavailabe */ + #define ETH_DMASR_TPS_Closing ((uint32_t)0x00700000) /* Running - closing Rx descriptor */ +#define ETH_DMASR_RPS ((uint32_t)0x000E0000) /* Receive process state */ + #define ETH_DMASR_RPS_Stopped ((uint32_t)0x00000000) /* Stopped - Reset or Stop Rx Command issued */ + #define ETH_DMASR_RPS_Fetching ((uint32_t)0x00020000) /* Running - fetching the Rx descriptor */ + #define ETH_DMASR_RPS_Waiting ((uint32_t)0x00060000) /* Running - waiting for packet */ + #define ETH_DMASR_RPS_Suspended ((uint32_t)0x00080000) /* Suspended - Rx Descriptor unavailable */ + #define ETH_DMASR_RPS_Closing ((uint32_t)0x000A0000) /* Running - closing descriptor */ + #define ETH_DMASR_RPS_Queuing ((uint32_t)0x000E0000) /* Running - queuing the recieve frame into host memory */ +#define ETH_DMASR_NIS ((uint32_t)0x00010000) /* Normal interrupt summary */ +#define ETH_DMASR_AIS ((uint32_t)0x00008000) /* Abnormal interrupt summary */ +#define ETH_DMASR_ERS ((uint32_t)0x00004000) /* Early receive status */ +#define ETH_DMASR_FBES ((uint32_t)0x00002000) /* Fatal bus error status */ +#define ETH_DMASR_ETS ((uint32_t)0x00000400) /* Early transmit status */ +#define ETH_DMASR_RWTS ((uint32_t)0x00000200) /* Receive watchdog timeout status */ +#define ETH_DMASR_RPSS ((uint32_t)0x00000100) /* Receive process stopped status */ +#define ETH_DMASR_RBUS ((uint32_t)0x00000080) /* Receive buffer unavailable status */ +#define ETH_DMASR_RS ((uint32_t)0x00000040) /* Receive status */ +#define ETH_DMASR_TUS ((uint32_t)0x00000020) /* Transmit underflow status */ +#define ETH_DMASR_ROS ((uint32_t)0x00000010) /* Receive overflow status */ +#define ETH_DMASR_TJTS ((uint32_t)0x00000008) /* Transmit jabber timeout status */ +#define ETH_DMASR_TBUS ((uint32_t)0x00000004) /* Transmit buffer unavailable status */ +#define ETH_DMASR_TPSS ((uint32_t)0x00000002) /* Transmit process stopped status */ +#define ETH_DMASR_TS ((uint32_t)0x00000001) /* Transmit status */ + +/* Bit definition for Ethernet DMA Operation Mode Register */ +#define ETH_DMAOMR_DTCEFD ((uint32_t)0x04000000) /* Disable Dropping of TCP/IP checksum error frames */ +#define ETH_DMAOMR_RSF ((uint32_t)0x02000000) /* Receive store and forward */ +#define ETH_DMAOMR_DFRF ((uint32_t)0x01000000) /* Disable flushing of received frames */ +#define ETH_DMAOMR_TSF ((uint32_t)0x00200000) /* Transmit store and forward */ +#define ETH_DMAOMR_FTF ((uint32_t)0x00100000) /* Flush transmit FIFO */ +#define ETH_DMAOMR_TTC ((uint32_t)0x0001C000) /* Transmit threshold control */ + #define ETH_DMAOMR_TTC_64Bytes ((uint32_t)0x00000000) /* threshold level of the MTL Transmit FIFO is 64 Bytes */ + #define ETH_DMAOMR_TTC_128Bytes ((uint32_t)0x00004000) /* threshold level of the MTL Transmit FIFO is 128 Bytes */ + #define ETH_DMAOMR_TTC_192Bytes ((uint32_t)0x00008000) /* threshold level of the MTL Transmit FIFO is 192 Bytes */ + #define ETH_DMAOMR_TTC_256Bytes ((uint32_t)0x0000C000) /* threshold level of the MTL Transmit FIFO is 256 Bytes */ + #define ETH_DMAOMR_TTC_40Bytes ((uint32_t)0x00010000) /* threshold level of the MTL Transmit FIFO is 40 Bytes */ + #define ETH_DMAOMR_TTC_32Bytes ((uint32_t)0x00014000) /* threshold level of the MTL Transmit FIFO is 32 Bytes */ + #define ETH_DMAOMR_TTC_24Bytes ((uint32_t)0x00018000) /* threshold level of the MTL Transmit FIFO is 24 Bytes */ + #define ETH_DMAOMR_TTC_16Bytes ((uint32_t)0x0001C000) /* threshold level of the MTL Transmit FIFO is 16 Bytes */ +#define ETH_DMAOMR_ST ((uint32_t)0x00002000) /* Start/stop transmission command */ +#define ETH_DMAOMR_FEF ((uint32_t)0x00000080) /* Forward error frames */ +#define ETH_DMAOMR_FUGF ((uint32_t)0x00000040) /* Forward undersized good frames */ +#define ETH_DMAOMR_RTC ((uint32_t)0x00000018) /* receive threshold control */ + #define ETH_DMAOMR_RTC_64Bytes ((uint32_t)0x00000000) /* threshold level of the MTL Receive FIFO is 64 Bytes */ + #define ETH_DMAOMR_RTC_32Bytes ((uint32_t)0x00000008) /* threshold level of the MTL Receive FIFO is 32 Bytes */ + #define ETH_DMAOMR_RTC_96Bytes ((uint32_t)0x00000010) /* threshold level of the MTL Receive FIFO is 96 Bytes */ + #define ETH_DMAOMR_RTC_128Bytes ((uint32_t)0x00000018) /* threshold level of the MTL Receive FIFO is 128 Bytes */ +#define ETH_DMAOMR_OSF ((uint32_t)0x00000004) /* operate on second frame */ +#define ETH_DMAOMR_SR ((uint32_t)0x00000002) /* Start/stop receive */ + +/* Bit definition for Ethernet DMA Interrupt Enable Register */ +#define ETH_DMAIER_NISE ((uint32_t)0x00010000) /* Normal interrupt summary enable */ +#define ETH_DMAIER_AISE ((uint32_t)0x00008000) /* Abnormal interrupt summary enable */ +#define ETH_DMAIER_ERIE ((uint32_t)0x00004000) /* Early receive interrupt enable */ +#define ETH_DMAIER_FBEIE ((uint32_t)0x00002000) /* Fatal bus error interrupt enable */ +#define ETH_DMAIER_ETIE ((uint32_t)0x00000400) /* Early transmit interrupt enable */ +#define ETH_DMAIER_RWTIE ((uint32_t)0x00000200) /* Receive watchdog timeout interrupt enable */ +#define ETH_DMAIER_RPSIE ((uint32_t)0x00000100) /* Receive process stopped interrupt enable */ +#define ETH_DMAIER_RBUIE ((uint32_t)0x00000080) /* Receive buffer unavailable interrupt enable */ +#define ETH_DMAIER_RIE ((uint32_t)0x00000040) /* Receive interrupt enable */ +#define ETH_DMAIER_TUIE ((uint32_t)0x00000020) /* Transmit Underflow interrupt enable */ +#define ETH_DMAIER_ROIE ((uint32_t)0x00000010) /* Receive Overflow interrupt enable */ +#define ETH_DMAIER_TJTIE ((uint32_t)0x00000008) /* Transmit jabber timeout interrupt enable */ +#define ETH_DMAIER_TBUIE ((uint32_t)0x00000004) /* Transmit buffer unavailable interrupt enable */ +#define ETH_DMAIER_TPSIE ((uint32_t)0x00000002) /* Transmit process stopped interrupt enable */ +#define ETH_DMAIER_TIE ((uint32_t)0x00000001) /* Transmit interrupt enable */ + +/* Bit definition for Ethernet DMA Missed Frame and Buffer Overflow Counter Register */ +#define ETH_DMAMFBOCR_OFOC ((uint32_t)0x10000000) /* Overflow bit for FIFO overflow counter */ +#define ETH_DMAMFBOCR_MFA ((uint32_t)0x0FFE0000) /* Number of frames missed by the application */ +#define ETH_DMAMFBOCR_OMFC ((uint32_t)0x00010000) /* Overflow bit for missed frame counter */ +#define ETH_DMAMFBOCR_MFC ((uint32_t)0x0000FFFF) /* Number of frames missed by the controller */ + +/* Bit definition for Ethernet DMA Current Host Transmit Descriptor Register */ +#define ETH_DMACHTDR_HTDAP ((uint32_t)0xFFFFFFFF) /* Host transmit descriptor address pointer */ + +/* Bit definition for Ethernet DMA Current Host Receive Descriptor Register */ +#define ETH_DMACHRDR_HRDAP ((uint32_t)0xFFFFFFFF) /* Host receive descriptor address pointer */ + +/* Bit definition for Ethernet DMA Current Host Transmit Buffer Address Register */ +#define ETH_DMACHTBAR_HTBAP ((uint32_t)0xFFFFFFFF) /* Host transmit buffer address pointer */ + +/* Bit definition for Ethernet DMA Current Host Receive Buffer Address Register */ +#define ETH_DMACHRBAR_HRBAP ((uint32_t)0xFFFFFFFF) /* Host receive buffer address pointer */ +#endif /* STM32F10X_CL */ + +/** + * @} + */ + + /** + * @} + */ + +#ifdef USE_STDPERIPH_DRIVER + #include "stm32f10x_conf.h" +#endif + +/** @addtogroup Exported_macro + * @{ + */ + +#define SET_BIT(REG, BIT) ((REG) |= (BIT)) + +#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) + +#define READ_BIT(REG, BIT) ((REG) & (BIT)) + +#define CLEAR_REG(REG) ((REG) = (0x0)) + +#define WRITE_REG(REG, VAL) ((REG) = (VAL)) + +#define READ_REG(REG) ((REG)) + +#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) + +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_H */ + +/** + * @} + */ + + /** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h new file mode 100755 index 0000000000..20b789b0dd --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/stm32f10x_conf.h @@ -0,0 +1,79 @@ +/** + ****************************************************************************** + * @file Project/STM32F10x_StdPeriph_Template/stm32f10x_conf.h + * @author MCD Application Team + * @version V3.5.0 + * @date 08-April-2011 + * @brief Library configuration file. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CONF_H +#define __STM32F10x_CONF_H + +/* Includes ------------------------------------------------------------------*/ +/* Uncomment/Comment the line below to enable/disable peripheral header file inclusion */ +#include "stm32f10x_adc.h" +#include "stm32f10x_bkp.h" +#include "stm32f10x_can.h" +#include "stm32f10x_cec.h" +#include "stm32f10x_crc.h" +#include "stm32f10x_dac.h" +#include "stm32f10x_dbgmcu.h" +#include "stm32f10x_dma.h" +#include "stm32f10x_exti.h" +#include "stm32f10x_flash.h" +#include "stm32f10x_fsmc.h" +#include "stm32f10x_gpio.h" +#include "stm32f10x_i2c.h" +#include "stm32f10x_iwdg.h" +#include "stm32f10x_pwr.h" +#include "stm32f10x_rcc.h" +#include "stm32f10x_rtc.h" +#include "stm32f10x_sdio.h" +#include "stm32f10x_spi.h" +#include "stm32f10x_tim.h" +#include "stm32f10x_usart.h" +#include "stm32f10x_wwdg.h" +#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */ + +extern void assert_param(int val); + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Uncomment the line below to expanse the "assert_param" macro in the + Standard Peripheral Library drivers code */ +// #define USE_FULL_ASSERT 1 + +/* Exported macro ------------------------------------------------------------*/ +#ifdef USE_FULL_ASSERT + +/** + * @brief The assert_param macro is used for function's parameters check. + * @param expr: If expr is false, it calls assert_failed function which reports + * the name of the source file and the source line number of the call + * that failed. If expr is true, it returns no value. + * @retval None + */ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(uint8_t* file, uint32_t line); +#else + #define assert_param(expr) ((void)0) +#endif /* USE_FULL_ASSERT */ + +#endif /* __STM32F10x_CONF_H */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c new file mode 100755 index 0000000000..1aa81520d7 --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.c @@ -0,0 +1,256 @@ +#include "stm32f10x.h" + +#define SYSCLK_FREQ_72MHz 72000000 + +/*!< Uncomment the following line if you need to relocate your vector Table in Internal SRAM. */ +/* #define VECT_TAB_SRAM */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ + +uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ + +__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; + +static void SetSysClock(void); + +/** + * @brief Setup the microcontroller system + * Initialize the Embedded Flash Interface, the PLL and update the + * SystemCoreClock variable. + * @note This function should be used only after reset. + * @param None + * @retval None + */ +void SystemInit (void) +{ + /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ + RCC->CFGR &= (uint32_t)0xF8FF0000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + /* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */ + /* Configure the Flash Latency cycles and enable prefetch buffer */ + SetSysClock(); + +#ifdef VECT_TAB_SRAM + SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ +#else + SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ +#endif +} + +/** + * @brief Update SystemCoreClock variable according to Clock Register Values. + * The SystemCoreClock variable contains the core clock (HCLK), it can + * be used by the user application to setup the SysTick timer or configure + * other parameters. + * + * @note Each time the core clock (HCLK) changes, this function must be called + * to update SystemCoreClock variable value. Otherwise, any configuration + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined + * constant and the selected clock source: + * + * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) + * + * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) + * + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * or HSI_VALUE(*) multiplied by the PLL factors. + * + * (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value + * 8 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value + * 8 MHz or 25 MHz, depedning on the product used), user has to ensure + * that HSE_VALUE is same as the real frequency of the crystal used. + * Otherwise, this function may have wrong result. + * + * - The result of this function could be not correct when using fractional + * value for HSE crystal. + * @param None + * @retval None + */ +void SystemCoreClockUpdate (void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0; + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } + else + { + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET) + {/* HSE oscillator clock divided by 2 */ + SystemCoreClock = (HSE_VALUE >> 1) * pllmull; + } + else + { + SystemCoreClock = HSE_VALUE * pllmull; + } + } + break; + + default: + SystemCoreClock = HSI_VALUE; + break; + } + + /* Compute HCLK clock frequency ----------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +// Set system clock to 72 (HSE) or 64 (HSI) MHz +static void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, HSEStatus = 0, HSIStatus = 0; + + /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/ + /* Enable HSE */ + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) + { + HSEStatus = (uint32_t)0x01; + } + else + { + HSEStatus = (uint32_t)0x00; + } + + if (HSEStatus == (uint32_t)0x01) + { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 2 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + + /* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9); + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0); + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08); + } + else + { /* If HSE fails to start-up, the application will have wrong clock configuration. User can add here some code to deal with this error */ + /* Enable HSI */ + RCC->CR |= ((uint32_t)RCC_CR_HSION); + StartUpCounter = 0; + do { + HSIStatus = RCC->CR & RCC_CR_HSIRDY; + StartUpCounter++; + } while((HSIStatus == 0) && (StartUpCounter != 0x0500)); + + /* If that was successfull, we configure the PLL to use HSI as entry clock and to generate a system clock frequency of 64 MHz */ + if ((RCC->CR & RCC_CR_HSIRDY) != RESET) { + /* Enable Prefetch Buffer */ + FLASH->ACR |= FLASH_ACR_PRFTBE; + + /* Flash 2 wait state */ + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + + /* HCLK = SYSCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + + /* PCLK2 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + + /* PCLK1 = HCLK */ + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + + /* PLL configuration: PLLCLK = HSI/2 * 16 = 64 MHz */ + + /* Set Bits to 0 */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + /* Set Bits to 1 */ + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLMULL16); + + /* Enable PLL */ + RCC->CR |= RCC_CR_PLLON; + + /* Wait till PLL is ready */ + while((RCC->CR & RCC_CR_PLLRDY) == 0); + + /* Select PLL as system clock source */ + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + + /* Wait till PLL is used as system clock source */ + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08); + SystemCoreClockUpdate(); + } + } +} diff --git a/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h new file mode 100755 index 0000000000..739f33283e --- /dev/null +++ b/src/baseflight/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x/system_stm32f10x.h @@ -0,0 +1,98 @@ +/** + ****************************************************************************** + * @file system_stm32f10x.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32f10x_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32F10X_H +#define __SYSTEM_STM32F10X_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32F10x_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32F10x_System_Exported_types + * @{ + */ + +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32F10x_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32F10X_H */ + +/** + * @} + */ + +/** + * @} + */ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/misc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/misc.h new file mode 100755 index 0000000000..7d401ca9be --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/misc.h @@ -0,0 +1,220 @@ +/** + ****************************************************************************** + * @file misc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the miscellaneous + * firmware library functions (add-on to CMSIS functions). + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __MISC_H +#define __MISC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup MISC + * @{ + */ + +/** @defgroup MISC_Exported_Types + * @{ + */ + +/** + * @brief NVIC Init Structure definition + */ + +typedef struct +{ + uint8_t NVIC_IRQChannel; /*!< Specifies the IRQ channel to be enabled or disabled. + This parameter can be a value of @ref IRQn_Type + (For the complete STM32 Devices IRQ Channels list, please + refer to stm32f10x.h file) */ + + uint8_t NVIC_IRQChannelPreemptionPriority; /*!< Specifies the pre-emption priority for the IRQ channel + specified in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + uint8_t NVIC_IRQChannelSubPriority; /*!< Specifies the subpriority level for the IRQ channel specified + in NVIC_IRQChannel. This parameter can be a value + between 0 and 15 as described in the table @ref NVIC_Priority_Table */ + + FunctionalState NVIC_IRQChannelCmd; /*!< Specifies whether the IRQ channel defined in NVIC_IRQChannel + will be enabled or disabled. + This parameter can be set either to ENABLE or DISABLE */ +} NVIC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup NVIC_Priority_Table + * @{ + */ + +/** +@code + The table below gives the allowed values of the pre-emption priority and subpriority according + to the Priority Grouping configuration performed by NVIC_PriorityGroupConfig function + ============================================================================================================================ + NVIC_PriorityGroup | NVIC_IRQChannelPreemptionPriority | NVIC_IRQChannelSubPriority | Description + ============================================================================================================================ + NVIC_PriorityGroup_0 | 0 | 0-15 | 0 bits for pre-emption priority + | | | 4 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_1 | 0-1 | 0-7 | 1 bits for pre-emption priority + | | | 3 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_2 | 0-3 | 0-3 | 2 bits for pre-emption priority + | | | 2 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_3 | 0-7 | 0-1 | 3 bits for pre-emption priority + | | | 1 bits for subpriority + ---------------------------------------------------------------------------------------------------------------------------- + NVIC_PriorityGroup_4 | 0-15 | 0 | 4 bits for pre-emption priority + | | | 0 bits for subpriority + ============================================================================================================================ +@endcode +*/ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Constants + * @{ + */ + +/** @defgroup Vector_Table_Base + * @{ + */ + +#define NVIC_VectTab_RAM ((uint32_t)0x20000000) +#define NVIC_VectTab_FLASH ((uint32_t)0x08000000) +#define IS_NVIC_VECTTAB(VECTTAB) (((VECTTAB) == NVIC_VectTab_RAM) || \ + ((VECTTAB) == NVIC_VectTab_FLASH)) +/** + * @} + */ + +/** @defgroup System_Low_Power + * @{ + */ + +#define NVIC_LP_SEVONPEND ((uint8_t)0x10) +#define NVIC_LP_SLEEPDEEP ((uint8_t)0x04) +#define NVIC_LP_SLEEPONEXIT ((uint8_t)0x02) +#define IS_NVIC_LP(LP) (((LP) == NVIC_LP_SEVONPEND) || \ + ((LP) == NVIC_LP_SLEEPDEEP) || \ + ((LP) == NVIC_LP_SLEEPONEXIT)) +/** + * @} + */ + +/** @defgroup Preemption_Priority_Group + * @{ + */ + +#define NVIC_PriorityGroup_0 ((uint32_t)0x700) /*!< 0 bits for pre-emption priority + 4 bits for subpriority */ +#define NVIC_PriorityGroup_1 ((uint32_t)0x600) /*!< 1 bits for pre-emption priority + 3 bits for subpriority */ +#define NVIC_PriorityGroup_2 ((uint32_t)0x500) /*!< 2 bits for pre-emption priority + 2 bits for subpriority */ +#define NVIC_PriorityGroup_3 ((uint32_t)0x400) /*!< 3 bits for pre-emption priority + 1 bits for subpriority */ +#define NVIC_PriorityGroup_4 ((uint32_t)0x300) /*!< 4 bits for pre-emption priority + 0 bits for subpriority */ + +#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PriorityGroup_0) || \ + ((GROUP) == NVIC_PriorityGroup_1) || \ + ((GROUP) == NVIC_PriorityGroup_2) || \ + ((GROUP) == NVIC_PriorityGroup_3) || \ + ((GROUP) == NVIC_PriorityGroup_4)) + +#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10) + +#define IS_NVIC_OFFSET(OFFSET) ((OFFSET) < 0x000FFFFF) + +/** + * @} + */ + +/** @defgroup SysTick_clock_source + * @{ + */ + +#define SysTick_CLKSource_HCLK_Div8 ((uint32_t)0xFFFFFFFB) +#define SysTick_CLKSource_HCLK ((uint32_t)0x00000004) +#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ + ((SOURCE) == SysTick_CLKSource_HCLK_Div8)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Exported_Functions + * @{ + */ + +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup); +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct); +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset); +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState); +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource); + +#ifdef __cplusplus +} +#endif + +#endif /* __MISC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h new file mode 100755 index 0000000000..d1b2653a66 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_adc.h @@ -0,0 +1,483 @@ +/** + ****************************************************************************** + * @file stm32f10x_adc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the ADC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_ADC_H +#define __STM32F10x_ADC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup ADC + * @{ + */ + +/** @defgroup ADC_Exported_Types + * @{ + */ + +/** + * @brief ADC Init structure definition + */ + +typedef struct +{ + uint32_t ADC_Mode; /*!< Configures the ADC to operate in independent or + dual mode. + This parameter can be a value of @ref ADC_mode */ + + FunctionalState ADC_ScanConvMode; /*!< Specifies whether the conversion is performed in + Scan (multichannels) or Single (one channel) mode. + This parameter can be set to ENABLE or DISABLE */ + + FunctionalState ADC_ContinuousConvMode; /*!< Specifies whether the conversion is performed in + Continuous or Single mode. + This parameter can be set to ENABLE or DISABLE. */ + + uint32_t ADC_ExternalTrigConv; /*!< Defines the external trigger used to start the analog + to digital conversion of regular channels. This parameter + can be a value of @ref ADC_external_trigger_sources_for_regular_channels_conversion */ + + uint32_t ADC_DataAlign; /*!< Specifies whether the ADC data alignment is left or right. + This parameter can be a value of @ref ADC_data_align */ + + uint8_t ADC_NbrOfChannel; /*!< Specifies the number of ADC channels that will be converted + using the sequencer for regular channel group. + This parameter must range from 1 to 16. */ +}ADC_InitTypeDef; +/** + * @} + */ + +/** @defgroup ADC_Exported_Constants + * @{ + */ + +#define IS_ADC_ALL_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC2) || \ + ((PERIPH) == ADC3)) + +#define IS_ADC_DMA_PERIPH(PERIPH) (((PERIPH) == ADC1) || \ + ((PERIPH) == ADC3)) + +/** @defgroup ADC_mode + * @{ + */ + +#define ADC_Mode_Independent ((uint32_t)0x00000000) +#define ADC_Mode_RegInjecSimult ((uint32_t)0x00010000) +#define ADC_Mode_RegSimult_AlterTrig ((uint32_t)0x00020000) +#define ADC_Mode_InjecSimult_FastInterl ((uint32_t)0x00030000) +#define ADC_Mode_InjecSimult_SlowInterl ((uint32_t)0x00040000) +#define ADC_Mode_InjecSimult ((uint32_t)0x00050000) +#define ADC_Mode_RegSimult ((uint32_t)0x00060000) +#define ADC_Mode_FastInterl ((uint32_t)0x00070000) +#define ADC_Mode_SlowInterl ((uint32_t)0x00080000) +#define ADC_Mode_AlterTrig ((uint32_t)0x00090000) + +#define IS_ADC_MODE(MODE) (((MODE) == ADC_Mode_Independent) || \ + ((MODE) == ADC_Mode_RegInjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult_AlterTrig) || \ + ((MODE) == ADC_Mode_InjecSimult_FastInterl) || \ + ((MODE) == ADC_Mode_InjecSimult_SlowInterl) || \ + ((MODE) == ADC_Mode_InjecSimult) || \ + ((MODE) == ADC_Mode_RegSimult) || \ + ((MODE) == ADC_Mode_FastInterl) || \ + ((MODE) == ADC_Mode_SlowInterl) || \ + ((MODE) == ADC_Mode_AlterTrig)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_regular_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigConv_T1_CC1 ((uint32_t)0x00000000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T1_CC2 ((uint32_t)0x00020000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T2_CC2 ((uint32_t)0x00060000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T3_TRGO ((uint32_t)0x00080000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_T4_CC4 ((uint32_t)0x000A0000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO ((uint32_t)0x000C0000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigConv_T1_CC3 ((uint32_t)0x00040000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigConv_None ((uint32_t)0x000E0000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigConv_T3_CC1 ((uint32_t)0x00000000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T2_CC3 ((uint32_t)0x00020000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_CC1 ((uint32_t)0x00060000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T8_TRGO ((uint32_t)0x00080000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC1 ((uint32_t)0x000A0000) /*!< For ADC3 only */ +#define ADC_ExternalTrigConv_T5_CC3 ((uint32_t)0x000C0000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_ExternalTrigConv_T1_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T1_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC2) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T4_CC4) || \ + ((REGTRIG) == ADC_ExternalTrigConv_Ext_IT11_TIM8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_None) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T3_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T2_CC3) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T8_TRGO) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC1) || \ + ((REGTRIG) == ADC_ExternalTrigConv_T5_CC3)) +/** + * @} + */ + +/** @defgroup ADC_data_align + * @{ + */ + +#define ADC_DataAlign_Right ((uint32_t)0x00000000) +#define ADC_DataAlign_Left ((uint32_t)0x00000800) +#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DataAlign_Right) || \ + ((ALIGN) == ADC_DataAlign_Left)) +/** + * @} + */ + +/** @defgroup ADC_channels + * @{ + */ + +#define ADC_Channel_0 ((uint8_t)0x00) +#define ADC_Channel_1 ((uint8_t)0x01) +#define ADC_Channel_2 ((uint8_t)0x02) +#define ADC_Channel_3 ((uint8_t)0x03) +#define ADC_Channel_4 ((uint8_t)0x04) +#define ADC_Channel_5 ((uint8_t)0x05) +#define ADC_Channel_6 ((uint8_t)0x06) +#define ADC_Channel_7 ((uint8_t)0x07) +#define ADC_Channel_8 ((uint8_t)0x08) +#define ADC_Channel_9 ((uint8_t)0x09) +#define ADC_Channel_10 ((uint8_t)0x0A) +#define ADC_Channel_11 ((uint8_t)0x0B) +#define ADC_Channel_12 ((uint8_t)0x0C) +#define ADC_Channel_13 ((uint8_t)0x0D) +#define ADC_Channel_14 ((uint8_t)0x0E) +#define ADC_Channel_15 ((uint8_t)0x0F) +#define ADC_Channel_16 ((uint8_t)0x10) +#define ADC_Channel_17 ((uint8_t)0x11) + +#define ADC_Channel_TempSensor ((uint8_t)ADC_Channel_16) +#define ADC_Channel_Vrefint ((uint8_t)ADC_Channel_17) + +#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) == ADC_Channel_0) || ((CHANNEL) == ADC_Channel_1) || \ + ((CHANNEL) == ADC_Channel_2) || ((CHANNEL) == ADC_Channel_3) || \ + ((CHANNEL) == ADC_Channel_4) || ((CHANNEL) == ADC_Channel_5) || \ + ((CHANNEL) == ADC_Channel_6) || ((CHANNEL) == ADC_Channel_7) || \ + ((CHANNEL) == ADC_Channel_8) || ((CHANNEL) == ADC_Channel_9) || \ + ((CHANNEL) == ADC_Channel_10) || ((CHANNEL) == ADC_Channel_11) || \ + ((CHANNEL) == ADC_Channel_12) || ((CHANNEL) == ADC_Channel_13) || \ + ((CHANNEL) == ADC_Channel_14) || ((CHANNEL) == ADC_Channel_15) || \ + ((CHANNEL) == ADC_Channel_16) || ((CHANNEL) == ADC_Channel_17)) +/** + * @} + */ + +/** @defgroup ADC_sampling_time + * @{ + */ + +#define ADC_SampleTime_1Cycles5 ((uint8_t)0x00) +#define ADC_SampleTime_7Cycles5 ((uint8_t)0x01) +#define ADC_SampleTime_13Cycles5 ((uint8_t)0x02) +#define ADC_SampleTime_28Cycles5 ((uint8_t)0x03) +#define ADC_SampleTime_41Cycles5 ((uint8_t)0x04) +#define ADC_SampleTime_55Cycles5 ((uint8_t)0x05) +#define ADC_SampleTime_71Cycles5 ((uint8_t)0x06) +#define ADC_SampleTime_239Cycles5 ((uint8_t)0x07) +#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SampleTime_1Cycles5) || \ + ((TIME) == ADC_SampleTime_7Cycles5) || \ + ((TIME) == ADC_SampleTime_13Cycles5) || \ + ((TIME) == ADC_SampleTime_28Cycles5) || \ + ((TIME) == ADC_SampleTime_41Cycles5) || \ + ((TIME) == ADC_SampleTime_55Cycles5) || \ + ((TIME) == ADC_SampleTime_71Cycles5) || \ + ((TIME) == ADC_SampleTime_239Cycles5)) +/** + * @} + */ + +/** @defgroup ADC_external_trigger_sources_for_injected_channels_conversion + * @{ + */ + +#define ADC_ExternalTrigInjecConv_T2_TRGO ((uint32_t)0x00002000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T2_CC1 ((uint32_t)0x00003000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T3_CC4 ((uint32_t)0x00004000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_T4_TRGO ((uint32_t)0x00005000) /*!< For ADC1 and ADC2 */ +#define ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4 ((uint32_t)0x00006000) /*!< For ADC1 and ADC2 */ + +#define ADC_ExternalTrigInjecConv_T1_TRGO ((uint32_t)0x00000000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_T1_CC4 ((uint32_t)0x00001000) /*!< For ADC1, ADC2 and ADC3 */ +#define ADC_ExternalTrigInjecConv_None ((uint32_t)0x00007000) /*!< For ADC1, ADC2 and ADC3 */ + +#define ADC_ExternalTrigInjecConv_T4_CC3 ((uint32_t)0x00002000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC2 ((uint32_t)0x00003000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T8_CC4 ((uint32_t)0x00004000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_TRGO ((uint32_t)0x00005000) /*!< For ADC3 only */ +#define ADC_ExternalTrigInjecConv_T5_CC4 ((uint32_t)0x00006000) /*!< For ADC3 only */ + +#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_ExternalTrigInjecConv_T1_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T1_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T2_CC1) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T3_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_None) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T4_CC3) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC2) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T8_CC4) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_TRGO) || \ + ((INJTRIG) == ADC_ExternalTrigInjecConv_T5_CC4)) +/** + * @} + */ + +/** @defgroup ADC_injected_channel_selection + * @{ + */ + +#define ADC_InjectedChannel_1 ((uint8_t)0x14) +#define ADC_InjectedChannel_2 ((uint8_t)0x18) +#define ADC_InjectedChannel_3 ((uint8_t)0x1C) +#define ADC_InjectedChannel_4 ((uint8_t)0x20) +#define IS_ADC_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) == ADC_InjectedChannel_1) || \ + ((CHANNEL) == ADC_InjectedChannel_2) || \ + ((CHANNEL) == ADC_InjectedChannel_3) || \ + ((CHANNEL) == ADC_InjectedChannel_4)) +/** + * @} + */ + +/** @defgroup ADC_analog_watchdog_selection + * @{ + */ + +#define ADC_AnalogWatchdog_SingleRegEnable ((uint32_t)0x00800200) +#define ADC_AnalogWatchdog_SingleInjecEnable ((uint32_t)0x00400200) +#define ADC_AnalogWatchdog_SingleRegOrInjecEnable ((uint32_t)0x00C00200) +#define ADC_AnalogWatchdog_AllRegEnable ((uint32_t)0x00800000) +#define ADC_AnalogWatchdog_AllInjecEnable ((uint32_t)0x00400000) +#define ADC_AnalogWatchdog_AllRegAllInjecEnable ((uint32_t)0x00C00000) +#define ADC_AnalogWatchdog_None ((uint32_t)0x00000000) + +#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_AnalogWatchdog_SingleRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_SingleRegOrInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_AllRegAllInjecEnable) || \ + ((WATCHDOG) == ADC_AnalogWatchdog_None)) +/** + * @} + */ + +/** @defgroup ADC_interrupts_definition + * @{ + */ + +#define ADC_IT_EOC ((uint16_t)0x0220) +#define ADC_IT_AWD ((uint16_t)0x0140) +#define ADC_IT_JEOC ((uint16_t)0x0480) + +#define IS_ADC_IT(IT) ((((IT) & (uint16_t)0xF81F) == 0x00) && ((IT) != 0x00)) + +#define IS_ADC_GET_IT(IT) (((IT) == ADC_IT_EOC) || ((IT) == ADC_IT_AWD) || \ + ((IT) == ADC_IT_JEOC)) +/** + * @} + */ + +/** @defgroup ADC_flags_definition + * @{ + */ + +#define ADC_FLAG_AWD ((uint8_t)0x01) +#define ADC_FLAG_EOC ((uint8_t)0x02) +#define ADC_FLAG_JEOC ((uint8_t)0x04) +#define ADC_FLAG_JSTRT ((uint8_t)0x08) +#define ADC_FLAG_STRT ((uint8_t)0x10) +#define IS_ADC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint8_t)0xE0) == 0x00) && ((FLAG) != 0x00)) +#define IS_ADC_GET_FLAG(FLAG) (((FLAG) == ADC_FLAG_AWD) || ((FLAG) == ADC_FLAG_EOC) || \ + ((FLAG) == ADC_FLAG_JEOC) || ((FLAG)== ADC_FLAG_JSTRT) || \ + ((FLAG) == ADC_FLAG_STRT)) +/** + * @} + */ + +/** @defgroup ADC_thresholds + * @{ + */ + +#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_offset + * @{ + */ + +#define IS_ADC_OFFSET(OFFSET) ((OFFSET) <= 0xFFF) + +/** + * @} + */ + +/** @defgroup ADC_injected_length + * @{ + */ + +#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x4)) + +/** + * @} + */ + +/** @defgroup ADC_injected_rank + * @{ + */ + +#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x4)) + +/** + * @} + */ + + +/** @defgroup ADC_regular_length + * @{ + */ + +#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 0x1) && ((LENGTH) <= 0x10)) +/** + * @} + */ + +/** @defgroup ADC_regular_rank + * @{ + */ + +#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 0x1) && ((RANK) <= 0x10)) + +/** + * @} + */ + +/** @defgroup ADC_regular_discontinuous_mode_number + * @{ + */ + +#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 0x1) && ((NUMBER) <= 0x8)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Exported_Functions + * @{ + */ + +void ADC_DeInit(ADC_TypeDef* ADCx); +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct); +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct); +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState); +void ADC_ResetCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_StartCalibration(ADC_TypeDef* ADCx); +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx); +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx); +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number); +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx); +uint32_t ADC_GetDualModeConversionValue(void); +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv); +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState); +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx); +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length); +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset); +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel); +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog); +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, uint16_t LowThreshold); +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel); +void ADC_TempSensorVrefintCmd(FunctionalState NewState); +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG); +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT); +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_ADC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h new file mode 100755 index 0000000000..b620753eff --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_bkp.h @@ -0,0 +1,195 @@ +/** + ****************************************************************************** + * @file stm32f10x_bkp.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the BKP firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_BKP_H +#define __STM32F10x_BKP_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup BKP + * @{ + */ + +/** @defgroup BKP_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Constants + * @{ + */ + +/** @defgroup Tamper_Pin_active_level + * @{ + */ + +#define BKP_TamperPinLevel_High ((uint16_t)0x0000) +#define BKP_TamperPinLevel_Low ((uint16_t)0x0001) +#define IS_BKP_TAMPER_PIN_LEVEL(LEVEL) (((LEVEL) == BKP_TamperPinLevel_High) || \ + ((LEVEL) == BKP_TamperPinLevel_Low)) +/** + * @} + */ + +/** @defgroup RTC_output_source_to_output_on_the_Tamper_pin + * @{ + */ + +#define BKP_RTCOutputSource_None ((uint16_t)0x0000) +#define BKP_RTCOutputSource_CalibClock ((uint16_t)0x0080) +#define BKP_RTCOutputSource_Alarm ((uint16_t)0x0100) +#define BKP_RTCOutputSource_Second ((uint16_t)0x0300) +#define IS_BKP_RTC_OUTPUT_SOURCE(SOURCE) (((SOURCE) == BKP_RTCOutputSource_None) || \ + ((SOURCE) == BKP_RTCOutputSource_CalibClock) || \ + ((SOURCE) == BKP_RTCOutputSource_Alarm) || \ + ((SOURCE) == BKP_RTCOutputSource_Second)) +/** + * @} + */ + +/** @defgroup Data_Backup_Register + * @{ + */ + +#define BKP_DR1 ((uint16_t)0x0004) +#define BKP_DR2 ((uint16_t)0x0008) +#define BKP_DR3 ((uint16_t)0x000C) +#define BKP_DR4 ((uint16_t)0x0010) +#define BKP_DR5 ((uint16_t)0x0014) +#define BKP_DR6 ((uint16_t)0x0018) +#define BKP_DR7 ((uint16_t)0x001C) +#define BKP_DR8 ((uint16_t)0x0020) +#define BKP_DR9 ((uint16_t)0x0024) +#define BKP_DR10 ((uint16_t)0x0028) +#define BKP_DR11 ((uint16_t)0x0040) +#define BKP_DR12 ((uint16_t)0x0044) +#define BKP_DR13 ((uint16_t)0x0048) +#define BKP_DR14 ((uint16_t)0x004C) +#define BKP_DR15 ((uint16_t)0x0050) +#define BKP_DR16 ((uint16_t)0x0054) +#define BKP_DR17 ((uint16_t)0x0058) +#define BKP_DR18 ((uint16_t)0x005C) +#define BKP_DR19 ((uint16_t)0x0060) +#define BKP_DR20 ((uint16_t)0x0064) +#define BKP_DR21 ((uint16_t)0x0068) +#define BKP_DR22 ((uint16_t)0x006C) +#define BKP_DR23 ((uint16_t)0x0070) +#define BKP_DR24 ((uint16_t)0x0074) +#define BKP_DR25 ((uint16_t)0x0078) +#define BKP_DR26 ((uint16_t)0x007C) +#define BKP_DR27 ((uint16_t)0x0080) +#define BKP_DR28 ((uint16_t)0x0084) +#define BKP_DR29 ((uint16_t)0x0088) +#define BKP_DR30 ((uint16_t)0x008C) +#define BKP_DR31 ((uint16_t)0x0090) +#define BKP_DR32 ((uint16_t)0x0094) +#define BKP_DR33 ((uint16_t)0x0098) +#define BKP_DR34 ((uint16_t)0x009C) +#define BKP_DR35 ((uint16_t)0x00A0) +#define BKP_DR36 ((uint16_t)0x00A4) +#define BKP_DR37 ((uint16_t)0x00A8) +#define BKP_DR38 ((uint16_t)0x00AC) +#define BKP_DR39 ((uint16_t)0x00B0) +#define BKP_DR40 ((uint16_t)0x00B4) +#define BKP_DR41 ((uint16_t)0x00B8) +#define BKP_DR42 ((uint16_t)0x00BC) + +#define IS_BKP_DR(DR) (((DR) == BKP_DR1) || ((DR) == BKP_DR2) || ((DR) == BKP_DR3) || \ + ((DR) == BKP_DR4) || ((DR) == BKP_DR5) || ((DR) == BKP_DR6) || \ + ((DR) == BKP_DR7) || ((DR) == BKP_DR8) || ((DR) == BKP_DR9) || \ + ((DR) == BKP_DR10) || ((DR) == BKP_DR11) || ((DR) == BKP_DR12) || \ + ((DR) == BKP_DR13) || ((DR) == BKP_DR14) || ((DR) == BKP_DR15) || \ + ((DR) == BKP_DR16) || ((DR) == BKP_DR17) || ((DR) == BKP_DR18) || \ + ((DR) == BKP_DR19) || ((DR) == BKP_DR20) || ((DR) == BKP_DR21) || \ + ((DR) == BKP_DR22) || ((DR) == BKP_DR23) || ((DR) == BKP_DR24) || \ + ((DR) == BKP_DR25) || ((DR) == BKP_DR26) || ((DR) == BKP_DR27) || \ + ((DR) == BKP_DR28) || ((DR) == BKP_DR29) || ((DR) == BKP_DR30) || \ + ((DR) == BKP_DR31) || ((DR) == BKP_DR32) || ((DR) == BKP_DR33) || \ + ((DR) == BKP_DR34) || ((DR) == BKP_DR35) || ((DR) == BKP_DR36) || \ + ((DR) == BKP_DR37) || ((DR) == BKP_DR38) || ((DR) == BKP_DR39) || \ + ((DR) == BKP_DR40) || ((DR) == BKP_DR41) || ((DR) == BKP_DR42)) + +#define IS_BKP_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x7F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Exported_Functions + * @{ + */ + +void BKP_DeInit(void); +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel); +void BKP_TamperPinCmd(FunctionalState NewState); +void BKP_ITConfig(FunctionalState NewState); +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource); +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue); +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data); +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR); +FlagStatus BKP_GetFlagStatus(void); +void BKP_ClearFlag(void); +ITStatus BKP_GetITStatus(void); +void BKP_ClearITPendingBit(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_BKP_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h new file mode 100755 index 0000000000..648f747cdc --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_can.h @@ -0,0 +1,697 @@ +/** + ****************************************************************************** + * @file stm32f10x_can.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CAN firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CAN_H +#define __STM32F10x_CAN_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CAN + * @{ + */ + +/** @defgroup CAN_Exported_Types + * @{ + */ + +#define IS_CAN_ALL_PERIPH(PERIPH) (((PERIPH) == CAN1) || \ + ((PERIPH) == CAN2)) + +/** + * @brief CAN init structure definition + */ + +typedef struct +{ + uint16_t CAN_Prescaler; /*!< Specifies the length of a time quantum. + It ranges from 1 to 1024. */ + + uint8_t CAN_Mode; /*!< Specifies the CAN operating mode. + This parameter can be a value of + @ref CAN_operating_mode */ + + uint8_t CAN_SJW; /*!< Specifies the maximum number of time quanta + the CAN hardware is allowed to lengthen or + shorten a bit to perform resynchronization. + This parameter can be a value of + @ref CAN_synchronisation_jump_width */ + + uint8_t CAN_BS1; /*!< Specifies the number of time quanta in Bit + Segment 1. This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_1 */ + + uint8_t CAN_BS2; /*!< Specifies the number of time quanta in Bit + Segment 2. + This parameter can be a value of + @ref CAN_time_quantum_in_bit_segment_2 */ + + FunctionalState CAN_TTCM; /*!< Enable or disable the time triggered + communication mode. This parameter can be set + either to ENABLE or DISABLE. */ + + FunctionalState CAN_ABOM; /*!< Enable or disable the automatic bus-off + management. This parameter can be set either + to ENABLE or DISABLE. */ + + FunctionalState CAN_AWUM; /*!< Enable or disable the automatic wake-up mode. + This parameter can be set either to ENABLE or + DISABLE. */ + + FunctionalState CAN_NART; /*!< Enable or disable the no-automatic + retransmission mode. This parameter can be + set either to ENABLE or DISABLE. */ + + FunctionalState CAN_RFLM; /*!< Enable or disable the Receive FIFO Locked mode. + This parameter can be set either to ENABLE + or DISABLE. */ + + FunctionalState CAN_TXFP; /*!< Enable or disable the transmit FIFO priority. + This parameter can be set either to ENABLE + or DISABLE. */ +} CAN_InitTypeDef; + +/** + * @brief CAN filter init structure definition + */ + +typedef struct +{ + uint16_t CAN_FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit + configuration, first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit + configuration, second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, + according to the mode (MSBs for a 32-bit configuration, + first one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, + according to the mode (LSBs for a 32-bit configuration, + second one for a 16-bit configuration). + This parameter can be a value between 0x0000 and 0xFFFF */ + + uint16_t CAN_FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. + This parameter can be a value of @ref CAN_filter_FIFO */ + + uint8_t CAN_FilterNumber; /*!< Specifies the filter which will be initialized. It ranges from 0 to 13. */ + + uint8_t CAN_FilterMode; /*!< Specifies the filter mode to be initialized. + This parameter can be a value of @ref CAN_filter_mode */ + + uint8_t CAN_FilterScale; /*!< Specifies the filter scale. + This parameter can be a value of @ref CAN_filter_scale */ + + FunctionalState CAN_FilterActivation; /*!< Enable or disable the filter. + This parameter can be set either to ENABLE or DISABLE. */ +} CAN_FilterInitTypeDef; + +/** + * @brief CAN Tx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be transmitted. This parameter can be a value + of @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the message that will + be transmitted. This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be + transmitted. This parameter can be a value between + 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be transmitted. It ranges from 0 + to 0xFF. */ +} CanTxMsg; + +/** + * @brief CAN Rx message structure definition + */ + +typedef struct +{ + uint32_t StdId; /*!< Specifies the standard identifier. + This parameter can be a value between 0 to 0x7FF. */ + + uint32_t ExtId; /*!< Specifies the extended identifier. + This parameter can be a value between 0 to 0x1FFFFFFF. */ + + uint8_t IDE; /*!< Specifies the type of identifier for the message that + will be received. This parameter can be a value of + @ref CAN_identifier_type */ + + uint8_t RTR; /*!< Specifies the type of frame for the received message. + This parameter can be a value of + @ref CAN_remote_transmission_request */ + + uint8_t DLC; /*!< Specifies the length of the frame that will be received. + This parameter can be a value between 0 to 8 */ + + uint8_t Data[8]; /*!< Contains the data to be received. It ranges from 0 to + 0xFF. */ + + uint8_t FMI; /*!< Specifies the index of the filter the message stored in + the mailbox passes through. This parameter can be a + value between 0 to 0xFF */ +} CanRxMsg; + +/** + * @} + */ + +/** @defgroup CAN_Exported_Constants + * @{ + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CAN_InitStatus_Failed ((uint8_t)0x00) /*!< CAN initialization failed */ +#define CAN_InitStatus_Success ((uint8_t)0x01) /*!< CAN initialization OK */ + +/** + * @} + */ + +/** @defgroup CAN_Mode + * @{ + */ + +#define CAN_Mode_Normal ((uint8_t)0x00) /*!< normal mode */ +#define CAN_Mode_LoopBack ((uint8_t)0x01) /*!< loopback mode */ +#define CAN_Mode_Silent ((uint8_t)0x02) /*!< silent mode */ +#define CAN_Mode_Silent_LoopBack ((uint8_t)0x03) /*!< loopback combined with silent mode */ + +#define IS_CAN_MODE(MODE) (((MODE) == CAN_Mode_Normal) || \ + ((MODE) == CAN_Mode_LoopBack)|| \ + ((MODE) == CAN_Mode_Silent) || \ + ((MODE) == CAN_Mode_Silent_LoopBack)) +/** + * @} + */ + + +/** + * @defgroup CAN_Operating_Mode + * @{ + */ +#define CAN_OperatingMode_Initialization ((uint8_t)0x00) /*!< Initialization mode */ +#define CAN_OperatingMode_Normal ((uint8_t)0x01) /*!< Normal mode */ +#define CAN_OperatingMode_Sleep ((uint8_t)0x02) /*!< sleep mode */ + + +#define IS_CAN_OPERATING_MODE(MODE) (((MODE) == CAN_OperatingMode_Initialization) ||\ + ((MODE) == CAN_OperatingMode_Normal)|| \ + ((MODE) == CAN_OperatingMode_Sleep)) +/** + * @} + */ + +/** + * @defgroup CAN_Mode_Status + * @{ + */ + +#define CAN_ModeStatus_Failed ((uint8_t)0x00) /*!< CAN entering the specific mode failed */ +#define CAN_ModeStatus_Success ((uint8_t)!CAN_ModeStatus_Failed) /*!< CAN entering the specific mode Succeed */ + + +/** + * @} + */ + +/** @defgroup CAN_synchronisation_jump_width + * @{ + */ + +#define CAN_SJW_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_SJW_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_SJW_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_SJW_4tq ((uint8_t)0x03) /*!< 4 time quantum */ + +#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1tq) || ((SJW) == CAN_SJW_2tq)|| \ + ((SJW) == CAN_SJW_3tq) || ((SJW) == CAN_SJW_4tq)) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_1 + * @{ + */ + +#define CAN_BS1_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS1_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS1_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS1_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS1_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS1_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS1_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS1_8tq ((uint8_t)0x07) /*!< 8 time quantum */ +#define CAN_BS1_9tq ((uint8_t)0x08) /*!< 9 time quantum */ +#define CAN_BS1_10tq ((uint8_t)0x09) /*!< 10 time quantum */ +#define CAN_BS1_11tq ((uint8_t)0x0A) /*!< 11 time quantum */ +#define CAN_BS1_12tq ((uint8_t)0x0B) /*!< 12 time quantum */ +#define CAN_BS1_13tq ((uint8_t)0x0C) /*!< 13 time quantum */ +#define CAN_BS1_14tq ((uint8_t)0x0D) /*!< 14 time quantum */ +#define CAN_BS1_15tq ((uint8_t)0x0E) /*!< 15 time quantum */ +#define CAN_BS1_16tq ((uint8_t)0x0F) /*!< 16 time quantum */ + +#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16tq) +/** + * @} + */ + +/** @defgroup CAN_time_quantum_in_bit_segment_2 + * @{ + */ + +#define CAN_BS2_1tq ((uint8_t)0x00) /*!< 1 time quantum */ +#define CAN_BS2_2tq ((uint8_t)0x01) /*!< 2 time quantum */ +#define CAN_BS2_3tq ((uint8_t)0x02) /*!< 3 time quantum */ +#define CAN_BS2_4tq ((uint8_t)0x03) /*!< 4 time quantum */ +#define CAN_BS2_5tq ((uint8_t)0x04) /*!< 5 time quantum */ +#define CAN_BS2_6tq ((uint8_t)0x05) /*!< 6 time quantum */ +#define CAN_BS2_7tq ((uint8_t)0x06) /*!< 7 time quantum */ +#define CAN_BS2_8tq ((uint8_t)0x07) /*!< 8 time quantum */ + +#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8tq) + +/** + * @} + */ + +/** @defgroup CAN_clock_prescaler + * @{ + */ + +#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1) && ((PRESCALER) <= 1024)) + +/** + * @} + */ + +/** @defgroup CAN_filter_number + * @{ + */ +#ifndef STM32F10X_CL + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 13) +#else + #define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup CAN_filter_mode + * @{ + */ + +#define CAN_FilterMode_IdMask ((uint8_t)0x00) /*!< identifier/mask mode */ +#define CAN_FilterMode_IdList ((uint8_t)0x01) /*!< identifier list mode */ + +#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FilterMode_IdMask) || \ + ((MODE) == CAN_FilterMode_IdList)) +/** + * @} + */ + +/** @defgroup CAN_filter_scale + * @{ + */ + +#define CAN_FilterScale_16bit ((uint8_t)0x00) /*!< Two 16-bit filters */ +#define CAN_FilterScale_32bit ((uint8_t)0x01) /*!< One 32-bit filter */ + +#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FilterScale_16bit) || \ + ((SCALE) == CAN_FilterScale_32bit)) + +/** + * @} + */ + +/** @defgroup CAN_filter_FIFO + * @{ + */ + +#define CAN_Filter_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ +#define CAN_Filter_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ +#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FilterFIFO0) || \ + ((FIFO) == CAN_FilterFIFO1)) +/** + * @} + */ + +/** @defgroup Start_bank_filter_for_slave_CAN + * @{ + */ +#define IS_CAN_BANKNUMBER(BANKNUMBER) (((BANKNUMBER) >= 1) && ((BANKNUMBER) <= 27)) +/** + * @} + */ + +/** @defgroup CAN_Tx + * @{ + */ + +#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) +#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FF)) +#define IS_CAN_EXTID(EXTID) ((EXTID) <= ((uint32_t)0x1FFFFFFF)) +#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) + +/** + * @} + */ + +/** @defgroup CAN_identifier_type + * @{ + */ + +#define CAN_Id_Standard ((uint32_t)0x00000000) /*!< Standard Id */ +#define CAN_Id_Extended ((uint32_t)0x00000004) /*!< Extended Id */ +#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_Id_Standard) || \ + ((IDTYPE) == CAN_Id_Extended)) +/** + * @} + */ + +/** @defgroup CAN_remote_transmission_request + * @{ + */ + +#define CAN_RTR_Data ((uint32_t)0x00000000) /*!< Data frame */ +#define CAN_RTR_Remote ((uint32_t)0x00000002) /*!< Remote frame */ +#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_Data) || ((RTR) == CAN_RTR_Remote)) + +/** + * @} + */ + +/** @defgroup CAN_transmit_constants + * @{ + */ + +#define CAN_TxStatus_Failed ((uint8_t)0x00)/*!< CAN transmission failed */ +#define CAN_TxStatus_Ok ((uint8_t)0x01) /*!< CAN transmission succeeded */ +#define CAN_TxStatus_Pending ((uint8_t)0x02) /*!< CAN transmission pending */ +#define CAN_TxStatus_NoMailBox ((uint8_t)0x04) /*!< CAN cell did not provide an empty mailbox */ + +/** + * @} + */ + +/** @defgroup CAN_receive_FIFO_number_constants + * @{ + */ + +#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ +#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ + +#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) + +/** + * @} + */ + +/** @defgroup CAN_sleep_constants + * @{ + */ + +#define CAN_Sleep_Failed ((uint8_t)0x00) /*!< CAN did not enter the sleep mode */ +#define CAN_Sleep_Ok ((uint8_t)0x01) /*!< CAN entered the sleep mode */ + +/** + * @} + */ + +/** @defgroup CAN_wake_up_constants + * @{ + */ + +#define CAN_WakeUp_Failed ((uint8_t)0x00) /*!< CAN did not leave the sleep mode */ +#define CAN_WakeUp_Ok ((uint8_t)0x01) /*!< CAN leaved the sleep mode */ + +/** + * @} + */ + +/** + * @defgroup CAN_Error_Code_constants + * @{ + */ + +#define CAN_ErrorCode_NoErr ((uint8_t)0x00) /*!< No Error */ +#define CAN_ErrorCode_StuffErr ((uint8_t)0x10) /*!< Stuff Error */ +#define CAN_ErrorCode_FormErr ((uint8_t)0x20) /*!< Form Error */ +#define CAN_ErrorCode_ACKErr ((uint8_t)0x30) /*!< Acknowledgment Error */ +#define CAN_ErrorCode_BitRecessiveErr ((uint8_t)0x40) /*!< Bit Recessive Error */ +#define CAN_ErrorCode_BitDominantErr ((uint8_t)0x50) /*!< Bit Dominant Error */ +#define CAN_ErrorCode_CRCErr ((uint8_t)0x60) /*!< CRC Error */ +#define CAN_ErrorCode_SoftwareSetErr ((uint8_t)0x70) /*!< Software Set Error */ + + +/** + * @} + */ + +/** @defgroup CAN_flags + * @{ + */ +/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() + and CAN_ClearFlag() functions. */ +/* If the flag is 0x1XXXXXXX, it means that it can only be used with CAN_GetFlagStatus() function. */ + +/* Transmit Flags */ +#define CAN_FLAG_RQCP0 ((uint32_t)0x38000001) /*!< Request MailBox0 Flag */ +#define CAN_FLAG_RQCP1 ((uint32_t)0x38000100) /*!< Request MailBox1 Flag */ +#define CAN_FLAG_RQCP2 ((uint32_t)0x38010000) /*!< Request MailBox2 Flag */ + +/* Receive Flags */ +#define CAN_FLAG_FMP0 ((uint32_t)0x12000003) /*!< FIFO 0 Message Pending Flag */ +#define CAN_FLAG_FF0 ((uint32_t)0x32000008) /*!< FIFO 0 Full Flag */ +#define CAN_FLAG_FOV0 ((uint32_t)0x32000010) /*!< FIFO 0 Overrun Flag */ +#define CAN_FLAG_FMP1 ((uint32_t)0x14000003) /*!< FIFO 1 Message Pending Flag */ +#define CAN_FLAG_FF1 ((uint32_t)0x34000008) /*!< FIFO 1 Full Flag */ +#define CAN_FLAG_FOV1 ((uint32_t)0x34000010) /*!< FIFO 1 Overrun Flag */ + +/* Operating Mode Flags */ +#define CAN_FLAG_WKU ((uint32_t)0x31000008) /*!< Wake up Flag */ +#define CAN_FLAG_SLAK ((uint32_t)0x31000012) /*!< Sleep acknowledge Flag */ +/* Note: When SLAK intterupt is disabled (SLKIE=0), no polling on SLAKI is possible. + In this case the SLAK bit can be polled.*/ + +/* Error Flags */ +#define CAN_FLAG_EWG ((uint32_t)0x10F00001) /*!< Error Warning Flag */ +#define CAN_FLAG_EPV ((uint32_t)0x10F00002) /*!< Error Passive Flag */ +#define CAN_FLAG_BOF ((uint32_t)0x10F00004) /*!< Bus-Off Flag */ +#define CAN_FLAG_LEC ((uint32_t)0x30F00070) /*!< Last error code Flag */ + +#define IS_CAN_GET_FLAG(FLAG) (((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_BOF) || \ + ((FLAG) == CAN_FLAG_EPV) || ((FLAG) == CAN_FLAG_EWG) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_FOV0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FMP0) || \ + ((FLAG) == CAN_FLAG_FOV1) || ((FLAG) == CAN_FLAG_FF1) || \ + ((FLAG) == CAN_FLAG_FMP1) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1)|| ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_SLAK )) + +#define IS_CAN_CLEAR_FLAG(FLAG)(((FLAG) == CAN_FLAG_LEC) || ((FLAG) == CAN_FLAG_RQCP2) || \ + ((FLAG) == CAN_FLAG_RQCP1) || ((FLAG) == CAN_FLAG_RQCP0) || \ + ((FLAG) == CAN_FLAG_FF0) || ((FLAG) == CAN_FLAG_FOV0) ||\ + ((FLAG) == CAN_FLAG_FF1) || ((FLAG) == CAN_FLAG_FOV1) || \ + ((FLAG) == CAN_FLAG_WKU) || ((FLAG) == CAN_FLAG_SLAK)) +/** + * @} + */ + + +/** @defgroup CAN_interrupts + * @{ + */ + + + +#define CAN_IT_TME ((uint32_t)0x00000001) /*!< Transmit mailbox empty Interrupt*/ + +/* Receive Interrupts */ +#define CAN_IT_FMP0 ((uint32_t)0x00000002) /*!< FIFO 0 message pending Interrupt*/ +#define CAN_IT_FF0 ((uint32_t)0x00000004) /*!< FIFO 0 full Interrupt*/ +#define CAN_IT_FOV0 ((uint32_t)0x00000008) /*!< FIFO 0 overrun Interrupt*/ +#define CAN_IT_FMP1 ((uint32_t)0x00000010) /*!< FIFO 1 message pending Interrupt*/ +#define CAN_IT_FF1 ((uint32_t)0x00000020) /*!< FIFO 1 full Interrupt*/ +#define CAN_IT_FOV1 ((uint32_t)0x00000040) /*!< FIFO 1 overrun Interrupt*/ + +/* Operating Mode Interrupts */ +#define CAN_IT_WKU ((uint32_t)0x00010000) /*!< Wake-up Interrupt*/ +#define CAN_IT_SLK ((uint32_t)0x00020000) /*!< Sleep acknowledge Interrupt*/ + +/* Error Interrupts */ +#define CAN_IT_EWG ((uint32_t)0x00000100) /*!< Error warning Interrupt*/ +#define CAN_IT_EPV ((uint32_t)0x00000200) /*!< Error passive Interrupt*/ +#define CAN_IT_BOF ((uint32_t)0x00000400) /*!< Bus-off Interrupt*/ +#define CAN_IT_LEC ((uint32_t)0x00000800) /*!< Last error code Interrupt*/ +#define CAN_IT_ERR ((uint32_t)0x00008000) /*!< Error Interrupt*/ + +/* Flags named as Interrupts : kept only for FW compatibility */ +#define CAN_IT_RQCP0 CAN_IT_TME +#define CAN_IT_RQCP1 CAN_IT_TME +#define CAN_IT_RQCP2 CAN_IT_TME + + +#define IS_CAN_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FMP0) ||\ + ((IT) == CAN_IT_FF0) || ((IT) == CAN_IT_FOV0) ||\ + ((IT) == CAN_IT_FMP1) || ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1) || ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +#define IS_CAN_CLEAR_IT(IT) (((IT) == CAN_IT_TME) || ((IT) == CAN_IT_FF0) ||\ + ((IT) == CAN_IT_FOV0)|| ((IT) == CAN_IT_FF1) ||\ + ((IT) == CAN_IT_FOV1)|| ((IT) == CAN_IT_EWG) ||\ + ((IT) == CAN_IT_EPV) || ((IT) == CAN_IT_BOF) ||\ + ((IT) == CAN_IT_LEC) || ((IT) == CAN_IT_ERR) ||\ + ((IT) == CAN_IT_WKU) || ((IT) == CAN_IT_SLK)) + +/** + * @} + */ + +/** @defgroup CAN_Legacy + * @{ + */ +#define CANINITFAILED CAN_InitStatus_Failed +#define CANINITOK CAN_InitStatus_Success +#define CAN_FilterFIFO0 CAN_Filter_FIFO0 +#define CAN_FilterFIFO1 CAN_Filter_FIFO1 +#define CAN_ID_STD CAN_Id_Standard +#define CAN_ID_EXT CAN_Id_Extended +#define CAN_RTR_DATA CAN_RTR_Data +#define CAN_RTR_REMOTE CAN_RTR_Remote +#define CANTXFAILE CAN_TxStatus_Failed +#define CANTXOK CAN_TxStatus_Ok +#define CANTXPENDING CAN_TxStatus_Pending +#define CAN_NO_MB CAN_TxStatus_NoMailBox +#define CANSLEEPFAILED CAN_Sleep_Failed +#define CANSLEEPOK CAN_Sleep_Ok +#define CANWAKEUPFAILED CAN_WakeUp_Failed +#define CANWAKEUPOK CAN_WakeUp_Ok + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Exported_Functions + * @{ + */ +/* Function used to set the CAN configuration to the default reset state *****/ +void CAN_DeInit(CAN_TypeDef* CANx); + +/* Initialization and Configuration functions *********************************/ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct); +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct); +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct); +void CAN_SlaveStartBank(uint8_t CAN_BankNumber); +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState); +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState); + +/* Transmit functions *********************************************************/ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage); +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox); +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox); + +/* Receive functions **********************************************************/ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage); +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber); +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber); + + +/* Operation modes functions **************************************************/ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode); +uint8_t CAN_Sleep(CAN_TypeDef* CANx); +uint8_t CAN_WakeUp(CAN_TypeDef* CANx); + +/* Error management functions *************************************************/ +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx); +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx); +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx); + +/* Interrupts and flags management functions **********************************/ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState); +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG); +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT); +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CAN_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h new file mode 100755 index 0000000000..a3f8fc7853 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_cec.h @@ -0,0 +1,210 @@ +/** + ****************************************************************************** + * @file stm32f10x_cec.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CEC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CEC_H +#define __STM32F10x_CEC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CEC + * @{ + */ + + +/** @defgroup CEC_Exported_Types + * @{ + */ + +/** + * @brief CEC Init structure definition + */ +typedef struct +{ + uint16_t CEC_BitTimingMode; /*!< Configures the CEC Bit Timing Error Mode. + This parameter can be a value of @ref CEC_BitTiming_Mode */ + uint16_t CEC_BitPeriodMode; /*!< Configures the CEC Bit Period Error Mode. + This parameter can be a value of @ref CEC_BitPeriod_Mode */ +}CEC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup CEC_Exported_Constants + * @{ + */ + +/** @defgroup CEC_BitTiming_Mode + * @{ + */ +#define CEC_BitTimingStdMode ((uint16_t)0x00) /*!< Bit timing error Standard Mode */ +#define CEC_BitTimingErrFreeMode CEC_CFGR_BTEM /*!< Bit timing error Free Mode */ + +#define IS_CEC_BIT_TIMING_ERROR_MODE(MODE) (((MODE) == CEC_BitTimingStdMode) || \ + ((MODE) == CEC_BitTimingErrFreeMode)) +/** + * @} + */ + +/** @defgroup CEC_BitPeriod_Mode + * @{ + */ +#define CEC_BitPeriodStdMode ((uint16_t)0x00) /*!< Bit period error Standard Mode */ +#define CEC_BitPeriodFlexibleMode CEC_CFGR_BPEM /*!< Bit period error Flexible Mode */ + +#define IS_CEC_BIT_PERIOD_ERROR_MODE(MODE) (((MODE) == CEC_BitPeriodStdMode) || \ + ((MODE) == CEC_BitPeriodFlexibleMode)) +/** + * @} + */ + + +/** @defgroup CEC_interrupts_definition + * @{ + */ +#define CEC_IT_TERR CEC_CSR_TERR +#define CEC_IT_TBTRF CEC_CSR_TBTRF +#define CEC_IT_RERR CEC_CSR_RERR +#define CEC_IT_RBTF CEC_CSR_RBTF +#define IS_CEC_GET_IT(IT) (((IT) == CEC_IT_TERR) || ((IT) == CEC_IT_TBTRF) || \ + ((IT) == CEC_IT_RERR) || ((IT) == CEC_IT_RBTF)) +/** + * @} + */ + + +/** @defgroup CEC_Own_Address + * @{ + */ +#define IS_CEC_ADDRESS(ADDRESS) ((ADDRESS) < 0x10) +/** + * @} + */ + +/** @defgroup CEC_Prescaler + * @{ + */ +#define IS_CEC_PRESCALER(PRESCALER) ((PRESCALER) <= 0x3FFF) + +/** + * @} + */ + +/** @defgroup CEC_flags_definition + * @{ + */ + +/** + * @brief ESR register flags + */ +#define CEC_FLAG_BTE ((uint32_t)0x10010000) +#define CEC_FLAG_BPE ((uint32_t)0x10020000) +#define CEC_FLAG_RBTFE ((uint32_t)0x10040000) +#define CEC_FLAG_SBE ((uint32_t)0x10080000) +#define CEC_FLAG_ACKE ((uint32_t)0x10100000) +#define CEC_FLAG_LINE ((uint32_t)0x10200000) +#define CEC_FLAG_TBTFE ((uint32_t)0x10400000) + +/** + * @brief CSR register flags + */ +#define CEC_FLAG_TEOM ((uint32_t)0x00000002) +#define CEC_FLAG_TERR ((uint32_t)0x00000004) +#define CEC_FLAG_TBTRF ((uint32_t)0x00000008) +#define CEC_FLAG_RSOM ((uint32_t)0x00000010) +#define CEC_FLAG_REOM ((uint32_t)0x00000020) +#define CEC_FLAG_RERR ((uint32_t)0x00000040) +#define CEC_FLAG_RBTF ((uint32_t)0x00000080) + +#define IS_CEC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFF03) == 0x00) && ((FLAG) != 0x00)) + +#define IS_CEC_GET_FLAG(FLAG) (((FLAG) == CEC_FLAG_BTE) || ((FLAG) == CEC_FLAG_BPE) || \ + ((FLAG) == CEC_FLAG_RBTFE) || ((FLAG)== CEC_FLAG_SBE) || \ + ((FLAG) == CEC_FLAG_ACKE) || ((FLAG) == CEC_FLAG_LINE) || \ + ((FLAG) == CEC_FLAG_TBTFE) || ((FLAG) == CEC_FLAG_TEOM) || \ + ((FLAG) == CEC_FLAG_TERR) || ((FLAG) == CEC_FLAG_TBTRF) || \ + ((FLAG) == CEC_FLAG_RSOM) || ((FLAG) == CEC_FLAG_REOM) || \ + ((FLAG) == CEC_FLAG_RERR) || ((FLAG) == CEC_FLAG_RBTF)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CEC_Exported_Functions + * @{ + */ +void CEC_DeInit(void); +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct); +void CEC_Cmd(FunctionalState NewState); +void CEC_ITConfig(FunctionalState NewState); +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress); +void CEC_SetPrescaler(uint16_t CEC_Prescaler); +void CEC_SendDataByte(uint8_t Data); +uint8_t CEC_ReceiveDataByte(void); +void CEC_StartOfMessage(void); +void CEC_EndOfMessageCmd(FunctionalState NewState); +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG); +void CEC_ClearFlag(uint32_t CEC_FLAG); +ITStatus CEC_GetITStatus(uint8_t CEC_IT); +void CEC_ClearITPendingBit(uint16_t CEC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CEC_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h new file mode 100755 index 0000000000..658a51cefd --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_crc.h @@ -0,0 +1,94 @@ +/** + ****************************************************************************** + * @file stm32f10x_crc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the CRC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CRC_H +#define __STM32F10x_CRC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup CRC + * @{ + */ + +/** @defgroup CRC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Exported_Functions + * @{ + */ + +void CRC_ResetDR(void); +uint32_t CRC_CalcCRC(uint32_t Data); +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength); +uint32_t CRC_GetCRC(void); +void CRC_SetIDRegister(uint8_t IDValue); +uint8_t CRC_GetIDRegister(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_CRC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h new file mode 100755 index 0000000000..710616412c --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dac.h @@ -0,0 +1,317 @@ +/** + ****************************************************************************** + * @file stm32f10x_dac.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DAC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DAC_H +#define __STM32F10x_DAC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DAC + * @{ + */ + +/** @defgroup DAC_Exported_Types + * @{ + */ + +/** + * @brief DAC Init structure definition + */ + +typedef struct +{ + uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. + This parameter can be a value of @ref DAC_trigger_selection */ + + uint32_t DAC_WaveGeneration; /*!< Specifies whether DAC channel noise waves or triangle waves + are generated, or whether no wave is generated. + This parameter can be a value of @ref DAC_wave_generation */ + + uint32_t DAC_LFSRUnmask_TriangleAmplitude; /*!< Specifies the LFSR mask for noise wave generation or + the maximum amplitude triangle generation for the DAC channel. + This parameter can be a value of @ref DAC_lfsrunmask_triangleamplitude */ + + uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. + This parameter can be a value of @ref DAC_output_buffer */ +}DAC_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DAC_Exported_Constants + * @{ + */ + +/** @defgroup DAC_trigger_selection + * @{ + */ + +#define DAC_Trigger_None ((uint32_t)0x00000000) /*!< Conversion is automatic once the DAC1_DHRxxxx register + has been loaded, and not by external trigger */ +#define DAC_Trigger_T6_TRGO ((uint32_t)0x00000004) /*!< TIM6 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T8_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in High-density devices*/ +#define DAC_Trigger_T3_TRGO ((uint32_t)0x0000000C) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel + only in Connectivity line, Medium-density and Low-density Value Line devices */ +#define DAC_Trigger_T7_TRGO ((uint32_t)0x00000014) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T5_TRGO ((uint32_t)0x0000001C) /*!< TIM5 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T15_TRGO ((uint32_t)0x0000001C) /*!< TIM15 TRGO selected as external conversion trigger for DAC channel + only in Medium-density and Low-density Value Line devices*/ +#define DAC_Trigger_T2_TRGO ((uint32_t)0x00000024) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_T4_TRGO ((uint32_t)0x0000002C) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Ext_IT9 ((uint32_t)0x00000034) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ +#define DAC_Trigger_Software ((uint32_t)0x0000003C) /*!< Conversion started by software trigger for DAC channel */ + +#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_Trigger_None) || \ + ((TRIGGER) == DAC_Trigger_T6_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T8_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T7_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T5_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T2_TRGO) || \ + ((TRIGGER) == DAC_Trigger_T4_TRGO) || \ + ((TRIGGER) == DAC_Trigger_Ext_IT9) || \ + ((TRIGGER) == DAC_Trigger_Software)) + +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_WaveGeneration_None ((uint32_t)0x00000000) +#define DAC_WaveGeneration_Noise ((uint32_t)0x00000040) +#define DAC_WaveGeneration_Triangle ((uint32_t)0x00000080) +#define IS_DAC_GENERATE_WAVE(WAVE) (((WAVE) == DAC_WaveGeneration_None) || \ + ((WAVE) == DAC_WaveGeneration_Noise) || \ + ((WAVE) == DAC_WaveGeneration_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_lfsrunmask_triangleamplitude + * @{ + */ + +#define DAC_LFSRUnmask_Bit0 ((uint32_t)0x00000000) /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ +#define DAC_LFSRUnmask_Bits1_0 ((uint32_t)0x00000100) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits2_0 ((uint32_t)0x00000200) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits3_0 ((uint32_t)0x00000300) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits4_0 ((uint32_t)0x00000400) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits5_0 ((uint32_t)0x00000500) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits6_0 ((uint32_t)0x00000600) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits7_0 ((uint32_t)0x00000700) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits8_0 ((uint32_t)0x00000800) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits9_0 ((uint32_t)0x00000900) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits10_0 ((uint32_t)0x00000A00) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ +#define DAC_LFSRUnmask_Bits11_0 ((uint32_t)0x00000B00) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ +#define DAC_TriangleAmplitude_1 ((uint32_t)0x00000000) /*!< Select max triangle amplitude of 1 */ +#define DAC_TriangleAmplitude_3 ((uint32_t)0x00000100) /*!< Select max triangle amplitude of 3 */ +#define DAC_TriangleAmplitude_7 ((uint32_t)0x00000200) /*!< Select max triangle amplitude of 7 */ +#define DAC_TriangleAmplitude_15 ((uint32_t)0x00000300) /*!< Select max triangle amplitude of 15 */ +#define DAC_TriangleAmplitude_31 ((uint32_t)0x00000400) /*!< Select max triangle amplitude of 31 */ +#define DAC_TriangleAmplitude_63 ((uint32_t)0x00000500) /*!< Select max triangle amplitude of 63 */ +#define DAC_TriangleAmplitude_127 ((uint32_t)0x00000600) /*!< Select max triangle amplitude of 127 */ +#define DAC_TriangleAmplitude_255 ((uint32_t)0x00000700) /*!< Select max triangle amplitude of 255 */ +#define DAC_TriangleAmplitude_511 ((uint32_t)0x00000800) /*!< Select max triangle amplitude of 511 */ +#define DAC_TriangleAmplitude_1023 ((uint32_t)0x00000900) /*!< Select max triangle amplitude of 1023 */ +#define DAC_TriangleAmplitude_2047 ((uint32_t)0x00000A00) /*!< Select max triangle amplitude of 2047 */ +#define DAC_TriangleAmplitude_4095 ((uint32_t)0x00000B00) /*!< Select max triangle amplitude of 4095 */ + +#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUnmask_Bit0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits1_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits2_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits3_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits4_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits5_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits6_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits7_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits8_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits9_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits10_0) || \ + ((VALUE) == DAC_LFSRUnmask_Bits11_0) || \ + ((VALUE) == DAC_TriangleAmplitude_1) || \ + ((VALUE) == DAC_TriangleAmplitude_3) || \ + ((VALUE) == DAC_TriangleAmplitude_7) || \ + ((VALUE) == DAC_TriangleAmplitude_15) || \ + ((VALUE) == DAC_TriangleAmplitude_31) || \ + ((VALUE) == DAC_TriangleAmplitude_63) || \ + ((VALUE) == DAC_TriangleAmplitude_127) || \ + ((VALUE) == DAC_TriangleAmplitude_255) || \ + ((VALUE) == DAC_TriangleAmplitude_511) || \ + ((VALUE) == DAC_TriangleAmplitude_1023) || \ + ((VALUE) == DAC_TriangleAmplitude_2047) || \ + ((VALUE) == DAC_TriangleAmplitude_4095)) +/** + * @} + */ + +/** @defgroup DAC_output_buffer + * @{ + */ + +#define DAC_OutputBuffer_Enable ((uint32_t)0x00000000) +#define DAC_OutputBuffer_Disable ((uint32_t)0x00000002) +#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OutputBuffer_Enable) || \ + ((STATE) == DAC_OutputBuffer_Disable)) +/** + * @} + */ + +/** @defgroup DAC_Channel_selection + * @{ + */ + +#define DAC_Channel_1 ((uint32_t)0x00000000) +#define DAC_Channel_2 ((uint32_t)0x00000010) +#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_Channel_1) || \ + ((CHANNEL) == DAC_Channel_2)) +/** + * @} + */ + +/** @defgroup DAC_data_alignment + * @{ + */ + +#define DAC_Align_12b_R ((uint32_t)0x00000000) +#define DAC_Align_12b_L ((uint32_t)0x00000004) +#define DAC_Align_8b_R ((uint32_t)0x00000008) +#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_Align_12b_R) || \ + ((ALIGN) == DAC_Align_12b_L) || \ + ((ALIGN) == DAC_Align_8b_R)) +/** + * @} + */ + +/** @defgroup DAC_wave_generation + * @{ + */ + +#define DAC_Wave_Noise ((uint32_t)0x00000040) +#define DAC_Wave_Triangle ((uint32_t)0x00000080) +#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_Wave_Noise) || \ + ((WAVE) == DAC_Wave_Triangle)) +/** + * @} + */ + +/** @defgroup DAC_data + * @{ + */ + +#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0) +/** + * @} + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** @defgroup DAC_interrupts_definition + * @{ + */ + +#define DAC_IT_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_IT(IT) (((IT) == DAC_IT_DMAUDR)) + +/** + * @} + */ + +/** @defgroup DAC_flags_definition + * @{ + */ + +#define DAC_FLAG_DMAUDR ((uint32_t)0x00002000) +#define IS_DAC_FLAG(FLAG) (((FLAG) == DAC_FLAG_DMAUDR)) + +/** + * @} + */ +#endif + +/** + * @} + */ + +/** @defgroup DAC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Exported_Functions + * @{ + */ + +void DAC_DeInit(void); +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct); +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct); +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState); +#endif +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState); +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState); +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState); +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data); +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1); +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel); +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG); +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG); +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT); +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DAC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h new file mode 100755 index 0000000000..1e6a68acb4 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dbgmcu.h @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DBGMCU + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DBGMCU_H +#define __STM32F10x_DBGMCU_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DBGMCU + * @{ + */ + +/** @defgroup DBGMCU_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Constants + * @{ + */ + +#define DBGMCU_SLEEP ((uint32_t)0x00000001) +#define DBGMCU_STOP ((uint32_t)0x00000002) +#define DBGMCU_STANDBY ((uint32_t)0x00000004) +#define DBGMCU_IWDG_STOP ((uint32_t)0x00000100) +#define DBGMCU_WWDG_STOP ((uint32_t)0x00000200) +#define DBGMCU_TIM1_STOP ((uint32_t)0x00000400) +#define DBGMCU_TIM2_STOP ((uint32_t)0x00000800) +#define DBGMCU_TIM3_STOP ((uint32_t)0x00001000) +#define DBGMCU_TIM4_STOP ((uint32_t)0x00002000) +#define DBGMCU_CAN1_STOP ((uint32_t)0x00004000) +#define DBGMCU_I2C1_SMBUS_TIMEOUT ((uint32_t)0x00008000) +#define DBGMCU_I2C2_SMBUS_TIMEOUT ((uint32_t)0x00010000) +#define DBGMCU_TIM8_STOP ((uint32_t)0x00020000) +#define DBGMCU_TIM5_STOP ((uint32_t)0x00040000) +#define DBGMCU_TIM6_STOP ((uint32_t)0x00080000) +#define DBGMCU_TIM7_STOP ((uint32_t)0x00100000) +#define DBGMCU_CAN2_STOP ((uint32_t)0x00200000) +#define DBGMCU_TIM15_STOP ((uint32_t)0x00400000) +#define DBGMCU_TIM16_STOP ((uint32_t)0x00800000) +#define DBGMCU_TIM17_STOP ((uint32_t)0x01000000) +#define DBGMCU_TIM12_STOP ((uint32_t)0x02000000) +#define DBGMCU_TIM13_STOP ((uint32_t)0x04000000) +#define DBGMCU_TIM14_STOP ((uint32_t)0x08000000) +#define DBGMCU_TIM9_STOP ((uint32_t)0x10000000) +#define DBGMCU_TIM10_STOP ((uint32_t)0x20000000) +#define DBGMCU_TIM11_STOP ((uint32_t)0x40000000) + +#define IS_DBGMCU_PERIPH(PERIPH) ((((PERIPH) & 0x800000F8) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Exported_Functions + * @{ + */ + +uint32_t DBGMCU_GetREVID(void); +uint32_t DBGMCU_GetDEVID(void); +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_DBGMCU_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h new file mode 100755 index 0000000000..b5dc6a80ab --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_dma.h @@ -0,0 +1,439 @@ +/** + ****************************************************************************** + * @file stm32f10x_dma.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the DMA firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_DMA_H +#define __STM32F10x_DMA_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup DMA + * @{ + */ + +/** @defgroup DMA_Exported_Types + * @{ + */ + +/** + * @brief DMA Init structure definition + */ + +typedef struct +{ + uint32_t DMA_PeripheralBaseAddr; /*!< Specifies the peripheral base address for DMAy Channelx. */ + + uint32_t DMA_MemoryBaseAddr; /*!< Specifies the memory base address for DMAy Channelx. */ + + uint32_t DMA_DIR; /*!< Specifies if the peripheral is the source or destination. + This parameter can be a value of @ref DMA_data_transfer_direction */ + + uint32_t DMA_BufferSize; /*!< Specifies the buffer size, in data unit, of the specified Channel. + The data unit is equal to the configuration set in DMA_PeripheralDataSize + or DMA_MemoryDataSize members depending in the transfer direction. */ + + uint32_t DMA_PeripheralInc; /*!< Specifies whether the Peripheral address register is incremented or not. + This parameter can be a value of @ref DMA_peripheral_incremented_mode */ + + uint32_t DMA_MemoryInc; /*!< Specifies whether the memory address register is incremented or not. + This parameter can be a value of @ref DMA_memory_incremented_mode */ + + uint32_t DMA_PeripheralDataSize; /*!< Specifies the Peripheral data width. + This parameter can be a value of @ref DMA_peripheral_data_size */ + + uint32_t DMA_MemoryDataSize; /*!< Specifies the Memory data width. + This parameter can be a value of @ref DMA_memory_data_size */ + + uint32_t DMA_Mode; /*!< Specifies the operation mode of the DMAy Channelx. + This parameter can be a value of @ref DMA_circular_normal_mode. + @note: The circular buffer mode cannot be used if the memory-to-memory + data transfer is configured on the selected Channel */ + + uint32_t DMA_Priority; /*!< Specifies the software priority for the DMAy Channelx. + This parameter can be a value of @ref DMA_priority_level */ + + uint32_t DMA_M2M; /*!< Specifies if the DMAy Channelx will be used in memory-to-memory transfer. + This parameter can be a value of @ref DMA_memory_to_memory */ +}DMA_InitTypeDef; + +/** + * @} + */ + +/** @defgroup DMA_Exported_Constants + * @{ + */ + +#define IS_DMA_ALL_PERIPH(PERIPH) (((PERIPH) == DMA1_Channel1) || \ + ((PERIPH) == DMA1_Channel2) || \ + ((PERIPH) == DMA1_Channel3) || \ + ((PERIPH) == DMA1_Channel4) || \ + ((PERIPH) == DMA1_Channel5) || \ + ((PERIPH) == DMA1_Channel6) || \ + ((PERIPH) == DMA1_Channel7) || \ + ((PERIPH) == DMA2_Channel1) || \ + ((PERIPH) == DMA2_Channel2) || \ + ((PERIPH) == DMA2_Channel3) || \ + ((PERIPH) == DMA2_Channel4) || \ + ((PERIPH) == DMA2_Channel5)) + +/** @defgroup DMA_data_transfer_direction + * @{ + */ + +#define DMA_DIR_PeripheralDST ((uint32_t)0x00000010) +#define DMA_DIR_PeripheralSRC ((uint32_t)0x00000000) +#define IS_DMA_DIR(DIR) (((DIR) == DMA_DIR_PeripheralDST) || \ + ((DIR) == DMA_DIR_PeripheralSRC)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_incremented_mode + * @{ + */ + +#define DMA_PeripheralInc_Enable ((uint32_t)0x00000040) +#define DMA_PeripheralInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PeripheralInc_Enable) || \ + ((STATE) == DMA_PeripheralInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_memory_incremented_mode + * @{ + */ + +#define DMA_MemoryInc_Enable ((uint32_t)0x00000080) +#define DMA_MemoryInc_Disable ((uint32_t)0x00000000) +#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MemoryInc_Enable) || \ + ((STATE) == DMA_MemoryInc_Disable)) +/** + * @} + */ + +/** @defgroup DMA_peripheral_data_size + * @{ + */ + +#define DMA_PeripheralDataSize_Byte ((uint32_t)0x00000000) +#define DMA_PeripheralDataSize_HalfWord ((uint32_t)0x00000100) +#define DMA_PeripheralDataSize_Word ((uint32_t)0x00000200) +#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PeripheralDataSize_Byte) || \ + ((SIZE) == DMA_PeripheralDataSize_HalfWord) || \ + ((SIZE) == DMA_PeripheralDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_memory_data_size + * @{ + */ + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) +#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MemoryDataSize_Byte) || \ + ((SIZE) == DMA_MemoryDataSize_HalfWord) || \ + ((SIZE) == DMA_MemoryDataSize_Word)) +/** + * @} + */ + +/** @defgroup DMA_circular_normal_mode + * @{ + */ + +#define DMA_Mode_Circular ((uint32_t)0x00000020) +#define DMA_Mode_Normal ((uint32_t)0x00000000) +#define IS_DMA_MODE(MODE) (((MODE) == DMA_Mode_Circular) || ((MODE) == DMA_Mode_Normal)) +/** + * @} + */ + +/** @defgroup DMA_priority_level + * @{ + */ + +#define DMA_Priority_VeryHigh ((uint32_t)0x00003000) +#define DMA_Priority_High ((uint32_t)0x00002000) +#define DMA_Priority_Medium ((uint32_t)0x00001000) +#define DMA_Priority_Low ((uint32_t)0x00000000) +#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_Priority_VeryHigh) || \ + ((PRIORITY) == DMA_Priority_High) || \ + ((PRIORITY) == DMA_Priority_Medium) || \ + ((PRIORITY) == DMA_Priority_Low)) +/** + * @} + */ + +/** @defgroup DMA_memory_to_memory + * @{ + */ + +#define DMA_M2M_Enable ((uint32_t)0x00004000) +#define DMA_M2M_Disable ((uint32_t)0x00000000) +#define IS_DMA_M2M_STATE(STATE) (((STATE) == DMA_M2M_Enable) || ((STATE) == DMA_M2M_Disable)) + +/** + * @} + */ + +/** @defgroup DMA_interrupts_definition + * @{ + */ + +#define DMA_IT_TC ((uint32_t)0x00000002) +#define DMA_IT_HT ((uint32_t)0x00000004) +#define DMA_IT_TE ((uint32_t)0x00000008) +#define IS_DMA_CONFIG_IT(IT) ((((IT) & 0xFFFFFFF1) == 0x00) && ((IT) != 0x00)) + +#define DMA1_IT_GL1 ((uint32_t)0x00000001) +#define DMA1_IT_TC1 ((uint32_t)0x00000002) +#define DMA1_IT_HT1 ((uint32_t)0x00000004) +#define DMA1_IT_TE1 ((uint32_t)0x00000008) +#define DMA1_IT_GL2 ((uint32_t)0x00000010) +#define DMA1_IT_TC2 ((uint32_t)0x00000020) +#define DMA1_IT_HT2 ((uint32_t)0x00000040) +#define DMA1_IT_TE2 ((uint32_t)0x00000080) +#define DMA1_IT_GL3 ((uint32_t)0x00000100) +#define DMA1_IT_TC3 ((uint32_t)0x00000200) +#define DMA1_IT_HT3 ((uint32_t)0x00000400) +#define DMA1_IT_TE3 ((uint32_t)0x00000800) +#define DMA1_IT_GL4 ((uint32_t)0x00001000) +#define DMA1_IT_TC4 ((uint32_t)0x00002000) +#define DMA1_IT_HT4 ((uint32_t)0x00004000) +#define DMA1_IT_TE4 ((uint32_t)0x00008000) +#define DMA1_IT_GL5 ((uint32_t)0x00010000) +#define DMA1_IT_TC5 ((uint32_t)0x00020000) +#define DMA1_IT_HT5 ((uint32_t)0x00040000) +#define DMA1_IT_TE5 ((uint32_t)0x00080000) +#define DMA1_IT_GL6 ((uint32_t)0x00100000) +#define DMA1_IT_TC6 ((uint32_t)0x00200000) +#define DMA1_IT_HT6 ((uint32_t)0x00400000) +#define DMA1_IT_TE6 ((uint32_t)0x00800000) +#define DMA1_IT_GL7 ((uint32_t)0x01000000) +#define DMA1_IT_TC7 ((uint32_t)0x02000000) +#define DMA1_IT_HT7 ((uint32_t)0x04000000) +#define DMA1_IT_TE7 ((uint32_t)0x08000000) + +#define DMA2_IT_GL1 ((uint32_t)0x10000001) +#define DMA2_IT_TC1 ((uint32_t)0x10000002) +#define DMA2_IT_HT1 ((uint32_t)0x10000004) +#define DMA2_IT_TE1 ((uint32_t)0x10000008) +#define DMA2_IT_GL2 ((uint32_t)0x10000010) +#define DMA2_IT_TC2 ((uint32_t)0x10000020) +#define DMA2_IT_HT2 ((uint32_t)0x10000040) +#define DMA2_IT_TE2 ((uint32_t)0x10000080) +#define DMA2_IT_GL3 ((uint32_t)0x10000100) +#define DMA2_IT_TC3 ((uint32_t)0x10000200) +#define DMA2_IT_HT3 ((uint32_t)0x10000400) +#define DMA2_IT_TE3 ((uint32_t)0x10000800) +#define DMA2_IT_GL4 ((uint32_t)0x10001000) +#define DMA2_IT_TC4 ((uint32_t)0x10002000) +#define DMA2_IT_HT4 ((uint32_t)0x10004000) +#define DMA2_IT_TE4 ((uint32_t)0x10008000) +#define DMA2_IT_GL5 ((uint32_t)0x10010000) +#define DMA2_IT_TC5 ((uint32_t)0x10020000) +#define DMA2_IT_HT5 ((uint32_t)0x10040000) +#define DMA2_IT_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_IT(IT) (((((IT) & 0xF0000000) == 0x00) || (((IT) & 0xEFF00000) == 0x00)) && ((IT) != 0x00)) + +#define IS_DMA_GET_IT(IT) (((IT) == DMA1_IT_GL1) || ((IT) == DMA1_IT_TC1) || \ + ((IT) == DMA1_IT_HT1) || ((IT) == DMA1_IT_TE1) || \ + ((IT) == DMA1_IT_GL2) || ((IT) == DMA1_IT_TC2) || \ + ((IT) == DMA1_IT_HT2) || ((IT) == DMA1_IT_TE2) || \ + ((IT) == DMA1_IT_GL3) || ((IT) == DMA1_IT_TC3) || \ + ((IT) == DMA1_IT_HT3) || ((IT) == DMA1_IT_TE3) || \ + ((IT) == DMA1_IT_GL4) || ((IT) == DMA1_IT_TC4) || \ + ((IT) == DMA1_IT_HT4) || ((IT) == DMA1_IT_TE4) || \ + ((IT) == DMA1_IT_GL5) || ((IT) == DMA1_IT_TC5) || \ + ((IT) == DMA1_IT_HT5) || ((IT) == DMA1_IT_TE5) || \ + ((IT) == DMA1_IT_GL6) || ((IT) == DMA1_IT_TC6) || \ + ((IT) == DMA1_IT_HT6) || ((IT) == DMA1_IT_TE6) || \ + ((IT) == DMA1_IT_GL7) || ((IT) == DMA1_IT_TC7) || \ + ((IT) == DMA1_IT_HT7) || ((IT) == DMA1_IT_TE7) || \ + ((IT) == DMA2_IT_GL1) || ((IT) == DMA2_IT_TC1) || \ + ((IT) == DMA2_IT_HT1) || ((IT) == DMA2_IT_TE1) || \ + ((IT) == DMA2_IT_GL2) || ((IT) == DMA2_IT_TC2) || \ + ((IT) == DMA2_IT_HT2) || ((IT) == DMA2_IT_TE2) || \ + ((IT) == DMA2_IT_GL3) || ((IT) == DMA2_IT_TC3) || \ + ((IT) == DMA2_IT_HT3) || ((IT) == DMA2_IT_TE3) || \ + ((IT) == DMA2_IT_GL4) || ((IT) == DMA2_IT_TC4) || \ + ((IT) == DMA2_IT_HT4) || ((IT) == DMA2_IT_TE4) || \ + ((IT) == DMA2_IT_GL5) || ((IT) == DMA2_IT_TC5) || \ + ((IT) == DMA2_IT_HT5) || ((IT) == DMA2_IT_TE5)) + +/** + * @} + */ + +/** @defgroup DMA_flags_definition + * @{ + */ +#define DMA1_FLAG_GL1 ((uint32_t)0x00000001) +#define DMA1_FLAG_TC1 ((uint32_t)0x00000002) +#define DMA1_FLAG_HT1 ((uint32_t)0x00000004) +#define DMA1_FLAG_TE1 ((uint32_t)0x00000008) +#define DMA1_FLAG_GL2 ((uint32_t)0x00000010) +#define DMA1_FLAG_TC2 ((uint32_t)0x00000020) +#define DMA1_FLAG_HT2 ((uint32_t)0x00000040) +#define DMA1_FLAG_TE2 ((uint32_t)0x00000080) +#define DMA1_FLAG_GL3 ((uint32_t)0x00000100) +#define DMA1_FLAG_TC3 ((uint32_t)0x00000200) +#define DMA1_FLAG_HT3 ((uint32_t)0x00000400) +#define DMA1_FLAG_TE3 ((uint32_t)0x00000800) +#define DMA1_FLAG_GL4 ((uint32_t)0x00001000) +#define DMA1_FLAG_TC4 ((uint32_t)0x00002000) +#define DMA1_FLAG_HT4 ((uint32_t)0x00004000) +#define DMA1_FLAG_TE4 ((uint32_t)0x00008000) +#define DMA1_FLAG_GL5 ((uint32_t)0x00010000) +#define DMA1_FLAG_TC5 ((uint32_t)0x00020000) +#define DMA1_FLAG_HT5 ((uint32_t)0x00040000) +#define DMA1_FLAG_TE5 ((uint32_t)0x00080000) +#define DMA1_FLAG_GL6 ((uint32_t)0x00100000) +#define DMA1_FLAG_TC6 ((uint32_t)0x00200000) +#define DMA1_FLAG_HT6 ((uint32_t)0x00400000) +#define DMA1_FLAG_TE6 ((uint32_t)0x00800000) +#define DMA1_FLAG_GL7 ((uint32_t)0x01000000) +#define DMA1_FLAG_TC7 ((uint32_t)0x02000000) +#define DMA1_FLAG_HT7 ((uint32_t)0x04000000) +#define DMA1_FLAG_TE7 ((uint32_t)0x08000000) + +#define DMA2_FLAG_GL1 ((uint32_t)0x10000001) +#define DMA2_FLAG_TC1 ((uint32_t)0x10000002) +#define DMA2_FLAG_HT1 ((uint32_t)0x10000004) +#define DMA2_FLAG_TE1 ((uint32_t)0x10000008) +#define DMA2_FLAG_GL2 ((uint32_t)0x10000010) +#define DMA2_FLAG_TC2 ((uint32_t)0x10000020) +#define DMA2_FLAG_HT2 ((uint32_t)0x10000040) +#define DMA2_FLAG_TE2 ((uint32_t)0x10000080) +#define DMA2_FLAG_GL3 ((uint32_t)0x10000100) +#define DMA2_FLAG_TC3 ((uint32_t)0x10000200) +#define DMA2_FLAG_HT3 ((uint32_t)0x10000400) +#define DMA2_FLAG_TE3 ((uint32_t)0x10000800) +#define DMA2_FLAG_GL4 ((uint32_t)0x10001000) +#define DMA2_FLAG_TC4 ((uint32_t)0x10002000) +#define DMA2_FLAG_HT4 ((uint32_t)0x10004000) +#define DMA2_FLAG_TE4 ((uint32_t)0x10008000) +#define DMA2_FLAG_GL5 ((uint32_t)0x10010000) +#define DMA2_FLAG_TC5 ((uint32_t)0x10020000) +#define DMA2_FLAG_HT5 ((uint32_t)0x10040000) +#define DMA2_FLAG_TE5 ((uint32_t)0x10080000) + +#define IS_DMA_CLEAR_FLAG(FLAG) (((((FLAG) & 0xF0000000) == 0x00) || (((FLAG) & 0xEFF00000) == 0x00)) && ((FLAG) != 0x00)) + +#define IS_DMA_GET_FLAG(FLAG) (((FLAG) == DMA1_FLAG_GL1) || ((FLAG) == DMA1_FLAG_TC1) || \ + ((FLAG) == DMA1_FLAG_HT1) || ((FLAG) == DMA1_FLAG_TE1) || \ + ((FLAG) == DMA1_FLAG_GL2) || ((FLAG) == DMA1_FLAG_TC2) || \ + ((FLAG) == DMA1_FLAG_HT2) || ((FLAG) == DMA1_FLAG_TE2) || \ + ((FLAG) == DMA1_FLAG_GL3) || ((FLAG) == DMA1_FLAG_TC3) || \ + ((FLAG) == DMA1_FLAG_HT3) || ((FLAG) == DMA1_FLAG_TE3) || \ + ((FLAG) == DMA1_FLAG_GL4) || ((FLAG) == DMA1_FLAG_TC4) || \ + ((FLAG) == DMA1_FLAG_HT4) || ((FLAG) == DMA1_FLAG_TE4) || \ + ((FLAG) == DMA1_FLAG_GL5) || ((FLAG) == DMA1_FLAG_TC5) || \ + ((FLAG) == DMA1_FLAG_HT5) || ((FLAG) == DMA1_FLAG_TE5) || \ + ((FLAG) == DMA1_FLAG_GL6) || ((FLAG) == DMA1_FLAG_TC6) || \ + ((FLAG) == DMA1_FLAG_HT6) || ((FLAG) == DMA1_FLAG_TE6) || \ + ((FLAG) == DMA1_FLAG_GL7) || ((FLAG) == DMA1_FLAG_TC7) || \ + ((FLAG) == DMA1_FLAG_HT7) || ((FLAG) == DMA1_FLAG_TE7) || \ + ((FLAG) == DMA2_FLAG_GL1) || ((FLAG) == DMA2_FLAG_TC1) || \ + ((FLAG) == DMA2_FLAG_HT1) || ((FLAG) == DMA2_FLAG_TE1) || \ + ((FLAG) == DMA2_FLAG_GL2) || ((FLAG) == DMA2_FLAG_TC2) || \ + ((FLAG) == DMA2_FLAG_HT2) || ((FLAG) == DMA2_FLAG_TE2) || \ + ((FLAG) == DMA2_FLAG_GL3) || ((FLAG) == DMA2_FLAG_TC3) || \ + ((FLAG) == DMA2_FLAG_HT3) || ((FLAG) == DMA2_FLAG_TE3) || \ + ((FLAG) == DMA2_FLAG_GL4) || ((FLAG) == DMA2_FLAG_TC4) || \ + ((FLAG) == DMA2_FLAG_HT4) || ((FLAG) == DMA2_FLAG_TE4) || \ + ((FLAG) == DMA2_FLAG_GL5) || ((FLAG) == DMA2_FLAG_TC5) || \ + ((FLAG) == DMA2_FLAG_HT5) || ((FLAG) == DMA2_FLAG_TE5)) +/** + * @} + */ + +/** @defgroup DMA_Buffer_Size + * @{ + */ + +#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x1) && ((SIZE) < 0x10000)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Exported_Functions + * @{ + */ + +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx); +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct); +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct); +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState); +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState); +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber); +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx); +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG); +void DMA_ClearFlag(uint32_t DMAy_FLAG); +ITStatus DMA_GetITStatus(uint32_t DMAy_IT); +void DMA_ClearITPendingBit(uint32_t DMAy_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_DMA_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h new file mode 100755 index 0000000000..a1ab7d03e0 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_exti.h @@ -0,0 +1,184 @@ +/** + ****************************************************************************** + * @file stm32f10x_exti.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the EXTI firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_EXTI_H +#define __STM32F10x_EXTI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup EXTI + * @{ + */ + +/** @defgroup EXTI_Exported_Types + * @{ + */ + +/** + * @brief EXTI mode enumeration + */ + +typedef enum +{ + EXTI_Mode_Interrupt = 0x00, + EXTI_Mode_Event = 0x04 +}EXTIMode_TypeDef; + +#define IS_EXTI_MODE(MODE) (((MODE) == EXTI_Mode_Interrupt) || ((MODE) == EXTI_Mode_Event)) + +/** + * @brief EXTI Trigger enumeration + */ + +typedef enum +{ + EXTI_Trigger_Rising = 0x08, + EXTI_Trigger_Falling = 0x0C, + EXTI_Trigger_Rising_Falling = 0x10 +}EXTITrigger_TypeDef; + +#define IS_EXTI_TRIGGER(TRIGGER) (((TRIGGER) == EXTI_Trigger_Rising) || \ + ((TRIGGER) == EXTI_Trigger_Falling) || \ + ((TRIGGER) == EXTI_Trigger_Rising_Falling)) +/** + * @brief EXTI Init Structure definition + */ + +typedef struct +{ + uint32_t EXTI_Line; /*!< Specifies the EXTI lines to be enabled or disabled. + This parameter can be any combination of @ref EXTI_Lines */ + + EXTIMode_TypeDef EXTI_Mode; /*!< Specifies the mode for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + EXTITrigger_TypeDef EXTI_Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. + This parameter can be a value of @ref EXTIMode_TypeDef */ + + FunctionalState EXTI_LineCmd; /*!< Specifies the new state of the selected EXTI lines. + This parameter can be set either to ENABLE or DISABLE */ +}EXTI_InitTypeDef; + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Constants + * @{ + */ + +/** @defgroup EXTI_Lines + * @{ + */ + +#define EXTI_Line0 ((uint32_t)0x00001) /*!< External interrupt line 0 */ +#define EXTI_Line1 ((uint32_t)0x00002) /*!< External interrupt line 1 */ +#define EXTI_Line2 ((uint32_t)0x00004) /*!< External interrupt line 2 */ +#define EXTI_Line3 ((uint32_t)0x00008) /*!< External interrupt line 3 */ +#define EXTI_Line4 ((uint32_t)0x00010) /*!< External interrupt line 4 */ +#define EXTI_Line5 ((uint32_t)0x00020) /*!< External interrupt line 5 */ +#define EXTI_Line6 ((uint32_t)0x00040) /*!< External interrupt line 6 */ +#define EXTI_Line7 ((uint32_t)0x00080) /*!< External interrupt line 7 */ +#define EXTI_Line8 ((uint32_t)0x00100) /*!< External interrupt line 8 */ +#define EXTI_Line9 ((uint32_t)0x00200) /*!< External interrupt line 9 */ +#define EXTI_Line10 ((uint32_t)0x00400) /*!< External interrupt line 10 */ +#define EXTI_Line11 ((uint32_t)0x00800) /*!< External interrupt line 11 */ +#define EXTI_Line12 ((uint32_t)0x01000) /*!< External interrupt line 12 */ +#define EXTI_Line13 ((uint32_t)0x02000) /*!< External interrupt line 13 */ +#define EXTI_Line14 ((uint32_t)0x04000) /*!< External interrupt line 14 */ +#define EXTI_Line15 ((uint32_t)0x08000) /*!< External interrupt line 15 */ +#define EXTI_Line16 ((uint32_t)0x10000) /*!< External interrupt line 16 Connected to the PVD Output */ +#define EXTI_Line17 ((uint32_t)0x20000) /*!< External interrupt line 17 Connected to the RTC Alarm event */ +#define EXTI_Line18 ((uint32_t)0x40000) /*!< External interrupt line 18 Connected to the USB Device/USB OTG FS + Wakeup from suspend event */ +#define EXTI_Line19 ((uint32_t)0x80000) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ + +#define IS_EXTI_LINE(LINE) ((((LINE) & (uint32_t)0xFFF00000) == 0x00) && ((LINE) != (uint16_t)0x00)) +#define IS_GET_EXTI_LINE(LINE) (((LINE) == EXTI_Line0) || ((LINE) == EXTI_Line1) || \ + ((LINE) == EXTI_Line2) || ((LINE) == EXTI_Line3) || \ + ((LINE) == EXTI_Line4) || ((LINE) == EXTI_Line5) || \ + ((LINE) == EXTI_Line6) || ((LINE) == EXTI_Line7) || \ + ((LINE) == EXTI_Line8) || ((LINE) == EXTI_Line9) || \ + ((LINE) == EXTI_Line10) || ((LINE) == EXTI_Line11) || \ + ((LINE) == EXTI_Line12) || ((LINE) == EXTI_Line13) || \ + ((LINE) == EXTI_Line14) || ((LINE) == EXTI_Line15) || \ + ((LINE) == EXTI_Line16) || ((LINE) == EXTI_Line17) || \ + ((LINE) == EXTI_Line18) || ((LINE) == EXTI_Line19)) + + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Exported_Functions + * @{ + */ + +void EXTI_DeInit(void); +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct); +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line); +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line); +void EXTI_ClearFlag(uint32_t EXTI_Line); +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line); +void EXTI_ClearITPendingBit(uint32_t EXTI_Line); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_EXTI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h new file mode 100755 index 0000000000..f46d4e873b --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_flash.h @@ -0,0 +1,426 @@ +/** + ****************************************************************************** + * @file stm32f10x_flash.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the FLASH + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FLASH_H +#define __STM32F10x_FLASH_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FLASH + * @{ + */ + +/** @defgroup FLASH_Exported_Types + * @{ + */ + +/** + * @brief FLASH Status + */ + +typedef enum +{ + FLASH_BUSY = 1, + FLASH_ERROR_PG, + FLASH_ERROR_WRP, + FLASH_COMPLETE, + FLASH_TIMEOUT +}FLASH_Status; + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Constants + * @{ + */ + +/** @defgroup Flash_Latency + * @{ + */ + +#define FLASH_Latency_0 ((uint32_t)0x00000000) /*!< FLASH Zero Latency cycle */ +#define FLASH_Latency_1 ((uint32_t)0x00000001) /*!< FLASH One Latency cycle */ +#define FLASH_Latency_2 ((uint32_t)0x00000002) /*!< FLASH Two Latency cycles */ +#define IS_FLASH_LATENCY(LATENCY) (((LATENCY) == FLASH_Latency_0) || \ + ((LATENCY) == FLASH_Latency_1) || \ + ((LATENCY) == FLASH_Latency_2)) +/** + * @} + */ + +/** @defgroup Half_Cycle_Enable_Disable + * @{ + */ + +#define FLASH_HalfCycleAccess_Enable ((uint32_t)0x00000008) /*!< FLASH Half Cycle Enable */ +#define FLASH_HalfCycleAccess_Disable ((uint32_t)0x00000000) /*!< FLASH Half Cycle Disable */ +#define IS_FLASH_HALFCYCLEACCESS_STATE(STATE) (((STATE) == FLASH_HalfCycleAccess_Enable) || \ + ((STATE) == FLASH_HalfCycleAccess_Disable)) +/** + * @} + */ + +/** @defgroup Prefetch_Buffer_Enable_Disable + * @{ + */ + +#define FLASH_PrefetchBuffer_Enable ((uint32_t)0x00000010) /*!< FLASH Prefetch Buffer Enable */ +#define FLASH_PrefetchBuffer_Disable ((uint32_t)0x00000000) /*!< FLASH Prefetch Buffer Disable */ +#define IS_FLASH_PREFETCHBUFFER_STATE(STATE) (((STATE) == FLASH_PrefetchBuffer_Enable) || \ + ((STATE) == FLASH_PrefetchBuffer_Disable)) +/** + * @} + */ + +/** @defgroup Option_Bytes_Write_Protection + * @{ + */ + +/* Values to be used with STM32 Low and Medium density devices */ +#define FLASH_WRProt_Pages0to3 ((uint32_t)0x00000001) /*!< STM32 Low and Medium density devices: Write protection of page 0 to 3 */ +#define FLASH_WRProt_Pages4to7 ((uint32_t)0x00000002) /*!< STM32 Low and Medium density devices: Write protection of page 4 to 7 */ +#define FLASH_WRProt_Pages8to11 ((uint32_t)0x00000004) /*!< STM32 Low and Medium density devices: Write protection of page 8 to 11 */ +#define FLASH_WRProt_Pages12to15 ((uint32_t)0x00000008) /*!< STM32 Low and Medium density devices: Write protection of page 12 to 15 */ +#define FLASH_WRProt_Pages16to19 ((uint32_t)0x00000010) /*!< STM32 Low and Medium density devices: Write protection of page 16 to 19 */ +#define FLASH_WRProt_Pages20to23 ((uint32_t)0x00000020) /*!< STM32 Low and Medium density devices: Write protection of page 20 to 23 */ +#define FLASH_WRProt_Pages24to27 ((uint32_t)0x00000040) /*!< STM32 Low and Medium density devices: Write protection of page 24 to 27 */ +#define FLASH_WRProt_Pages28to31 ((uint32_t)0x00000080) /*!< STM32 Low and Medium density devices: Write protection of page 28 to 31 */ + +/* Values to be used with STM32 Medium-density devices */ +#define FLASH_WRProt_Pages32to35 ((uint32_t)0x00000100) /*!< STM32 Medium-density devices: Write protection of page 32 to 35 */ +#define FLASH_WRProt_Pages36to39 ((uint32_t)0x00000200) /*!< STM32 Medium-density devices: Write protection of page 36 to 39 */ +#define FLASH_WRProt_Pages40to43 ((uint32_t)0x00000400) /*!< STM32 Medium-density devices: Write protection of page 40 to 43 */ +#define FLASH_WRProt_Pages44to47 ((uint32_t)0x00000800) /*!< STM32 Medium-density devices: Write protection of page 44 to 47 */ +#define FLASH_WRProt_Pages48to51 ((uint32_t)0x00001000) /*!< STM32 Medium-density devices: Write protection of page 48 to 51 */ +#define FLASH_WRProt_Pages52to55 ((uint32_t)0x00002000) /*!< STM32 Medium-density devices: Write protection of page 52 to 55 */ +#define FLASH_WRProt_Pages56to59 ((uint32_t)0x00004000) /*!< STM32 Medium-density devices: Write protection of page 56 to 59 */ +#define FLASH_WRProt_Pages60to63 ((uint32_t)0x00008000) /*!< STM32 Medium-density devices: Write protection of page 60 to 63 */ +#define FLASH_WRProt_Pages64to67 ((uint32_t)0x00010000) /*!< STM32 Medium-density devices: Write protection of page 64 to 67 */ +#define FLASH_WRProt_Pages68to71 ((uint32_t)0x00020000) /*!< STM32 Medium-density devices: Write protection of page 68 to 71 */ +#define FLASH_WRProt_Pages72to75 ((uint32_t)0x00040000) /*!< STM32 Medium-density devices: Write protection of page 72 to 75 */ +#define FLASH_WRProt_Pages76to79 ((uint32_t)0x00080000) /*!< STM32 Medium-density devices: Write protection of page 76 to 79 */ +#define FLASH_WRProt_Pages80to83 ((uint32_t)0x00100000) /*!< STM32 Medium-density devices: Write protection of page 80 to 83 */ +#define FLASH_WRProt_Pages84to87 ((uint32_t)0x00200000) /*!< STM32 Medium-density devices: Write protection of page 84 to 87 */ +#define FLASH_WRProt_Pages88to91 ((uint32_t)0x00400000) /*!< STM32 Medium-density devices: Write protection of page 88 to 91 */ +#define FLASH_WRProt_Pages92to95 ((uint32_t)0x00800000) /*!< STM32 Medium-density devices: Write protection of page 92 to 95 */ +#define FLASH_WRProt_Pages96to99 ((uint32_t)0x01000000) /*!< STM32 Medium-density devices: Write protection of page 96 to 99 */ +#define FLASH_WRProt_Pages100to103 ((uint32_t)0x02000000) /*!< STM32 Medium-density devices: Write protection of page 100 to 103 */ +#define FLASH_WRProt_Pages104to107 ((uint32_t)0x04000000) /*!< STM32 Medium-density devices: Write protection of page 104 to 107 */ +#define FLASH_WRProt_Pages108to111 ((uint32_t)0x08000000) /*!< STM32 Medium-density devices: Write protection of page 108 to 111 */ +#define FLASH_WRProt_Pages112to115 ((uint32_t)0x10000000) /*!< STM32 Medium-density devices: Write protection of page 112 to 115 */ +#define FLASH_WRProt_Pages116to119 ((uint32_t)0x20000000) /*!< STM32 Medium-density devices: Write protection of page 115 to 119 */ +#define FLASH_WRProt_Pages120to123 ((uint32_t)0x40000000) /*!< STM32 Medium-density devices: Write protection of page 120 to 123 */ +#define FLASH_WRProt_Pages124to127 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 124 to 127 */ + +/* Values to be used with STM32 High-density and STM32F10X Connectivity line devices */ +#define FLASH_WRProt_Pages0to1 ((uint32_t)0x00000001) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 0 to 1 */ +#define FLASH_WRProt_Pages2to3 ((uint32_t)0x00000002) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 2 to 3 */ +#define FLASH_WRProt_Pages4to5 ((uint32_t)0x00000004) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 4 to 5 */ +#define FLASH_WRProt_Pages6to7 ((uint32_t)0x00000008) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 6 to 7 */ +#define FLASH_WRProt_Pages8to9 ((uint32_t)0x00000010) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 8 to 9 */ +#define FLASH_WRProt_Pages10to11 ((uint32_t)0x00000020) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 10 to 11 */ +#define FLASH_WRProt_Pages12to13 ((uint32_t)0x00000040) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 12 to 13 */ +#define FLASH_WRProt_Pages14to15 ((uint32_t)0x00000080) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 14 to 15 */ +#define FLASH_WRProt_Pages16to17 ((uint32_t)0x00000100) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 16 to 17 */ +#define FLASH_WRProt_Pages18to19 ((uint32_t)0x00000200) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 18 to 19 */ +#define FLASH_WRProt_Pages20to21 ((uint32_t)0x00000400) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 20 to 21 */ +#define FLASH_WRProt_Pages22to23 ((uint32_t)0x00000800) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 22 to 23 */ +#define FLASH_WRProt_Pages24to25 ((uint32_t)0x00001000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 24 to 25 */ +#define FLASH_WRProt_Pages26to27 ((uint32_t)0x00002000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 26 to 27 */ +#define FLASH_WRProt_Pages28to29 ((uint32_t)0x00004000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 28 to 29 */ +#define FLASH_WRProt_Pages30to31 ((uint32_t)0x00008000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 30 to 31 */ +#define FLASH_WRProt_Pages32to33 ((uint32_t)0x00010000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 32 to 33 */ +#define FLASH_WRProt_Pages34to35 ((uint32_t)0x00020000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 34 to 35 */ +#define FLASH_WRProt_Pages36to37 ((uint32_t)0x00040000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 36 to 37 */ +#define FLASH_WRProt_Pages38to39 ((uint32_t)0x00080000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 38 to 39 */ +#define FLASH_WRProt_Pages40to41 ((uint32_t)0x00100000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 40 to 41 */ +#define FLASH_WRProt_Pages42to43 ((uint32_t)0x00200000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 42 to 43 */ +#define FLASH_WRProt_Pages44to45 ((uint32_t)0x00400000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 44 to 45 */ +#define FLASH_WRProt_Pages46to47 ((uint32_t)0x00800000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 46 to 47 */ +#define FLASH_WRProt_Pages48to49 ((uint32_t)0x01000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 48 to 49 */ +#define FLASH_WRProt_Pages50to51 ((uint32_t)0x02000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 50 to 51 */ +#define FLASH_WRProt_Pages52to53 ((uint32_t)0x04000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 52 to 53 */ +#define FLASH_WRProt_Pages54to55 ((uint32_t)0x08000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 54 to 55 */ +#define FLASH_WRProt_Pages56to57 ((uint32_t)0x10000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 56 to 57 */ +#define FLASH_WRProt_Pages58to59 ((uint32_t)0x20000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 58 to 59 */ +#define FLASH_WRProt_Pages60to61 ((uint32_t)0x40000000) /*!< STM32 High-density, XL-density and Connectivity line devices: + Write protection of page 60 to 61 */ +#define FLASH_WRProt_Pages62to127 ((uint32_t)0x80000000) /*!< STM32 Connectivity line devices: Write protection of page 62 to 127 */ +#define FLASH_WRProt_Pages62to255 ((uint32_t)0x80000000) /*!< STM32 Medium-density devices: Write protection of page 62 to 255 */ +#define FLASH_WRProt_Pages62to511 ((uint32_t)0x80000000) /*!< STM32 XL-density devices: Write protection of page 62 to 511 */ + +#define FLASH_WRProt_AllPages ((uint32_t)0xFFFFFFFF) /*!< Write protection of all Pages */ + +#define IS_FLASH_WRPROT_PAGE(PAGE) (((PAGE) != 0x00000000)) + +#define IS_FLASH_ADDRESS(ADDRESS) (((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) + +#define IS_OB_DATA_ADDRESS(ADDRESS) (((ADDRESS) == 0x1FFFF804) || ((ADDRESS) == 0x1FFFF806)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_IWatchdog + * @{ + */ + +#define OB_IWDG_SW ((uint16_t)0x0001) /*!< Software IWDG selected */ +#define OB_IWDG_HW ((uint16_t)0x0000) /*!< Hardware IWDG selected */ +#define IS_OB_IWDG_SOURCE(SOURCE) (((SOURCE) == OB_IWDG_SW) || ((SOURCE) == OB_IWDG_HW)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STOP + * @{ + */ + +#define OB_STOP_NoRST ((uint16_t)0x0002) /*!< No reset generated when entering in STOP */ +#define OB_STOP_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STOP */ +#define IS_OB_STOP_SOURCE(SOURCE) (((SOURCE) == OB_STOP_NoRST) || ((SOURCE) == OB_STOP_RST)) + +/** + * @} + */ + +/** @defgroup Option_Bytes_nRST_STDBY + * @{ + */ + +#define OB_STDBY_NoRST ((uint16_t)0x0004) /*!< No reset generated when entering in STANDBY */ +#define OB_STDBY_RST ((uint16_t)0x0000) /*!< Reset generated when entering in STANDBY */ +#define IS_OB_STDBY_SOURCE(SOURCE) (((SOURCE) == OB_STDBY_NoRST) || ((SOURCE) == OB_STDBY_RST)) + +#ifdef STM32F10X_XL +/** + * @} + */ +/** @defgroup FLASH_Boot + * @{ + */ +#define FLASH_BOOT_Bank1 ((uint16_t)0x0000) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank1(Default) */ +#define FLASH_BOOT_Bank2 ((uint16_t)0x0001) /*!< At startup, if boot pins are set in boot from user Flash position + and this parameter is selected the device will boot from Bank 2 or Bank 1, + depending on the activation of the bank */ +#define IS_FLASH_BOOT(BOOT) (((BOOT) == FLASH_BOOT_Bank1) || ((BOOT) == FLASH_BOOT_Bank2)) +#endif +/** + * @} + */ +/** @defgroup FLASH_Interrupts + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_IT_BANK2_ERROR ((uint32_t)0x80000400) /*!< FPEC BANK2 error interrupt source */ +#define FLASH_IT_BANK2_EOP ((uint32_t)0x80001000) /*!< End of FLASH BANK2 Operation Interrupt source */ + +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH BANK1 Operation Interrupt source */ +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0x7FFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#else +#define FLASH_IT_ERROR ((uint32_t)0x00000400) /*!< FPEC error interrupt source */ +#define FLASH_IT_EOP ((uint32_t)0x00001000) /*!< End of FLASH Operation Interrupt source */ +#define FLASH_IT_BANK1_ERROR FLASH_IT_ERROR /*!< FPEC BANK1 error interrupt source */ +#define FLASH_IT_BANK1_EOP FLASH_IT_EOP /*!< End of FLASH BANK1 Operation Interrupt source */ + +#define IS_FLASH_IT(IT) ((((IT) & (uint32_t)0xFFFFEBFF) == 0x00000000) && (((IT) != 0x00000000))) +#endif + +/** + * @} + */ + +/** @defgroup FLASH_Flags + * @{ + */ +#ifdef STM32F10X_XL +#define FLASH_FLAG_BANK2_BSY ((uint32_t)0x80000001) /*!< FLASH BANK2 Busy flag */ +#define FLASH_FLAG_BANK2_EOP ((uint32_t)0x80000020) /*!< FLASH BANK2 End of Operation flag */ +#define FLASH_FLAG_BANK2_PGERR ((uint32_t)0x80000004) /*!< FLASH BANK2 Program error flag */ +#define FLASH_FLAG_BANK2_WRPRTERR ((uint32_t)0x80000010) /*!< FLASH BANK2 Write protected error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0x7FFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)|| \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK2_BSY) || ((FLAG) == FLASH_FLAG_BANK2_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK2_PGERR) || ((FLAG) == FLASH_FLAG_BANK2_WRPRTERR)) +#else +#define FLASH_FLAG_BSY ((uint32_t)0x00000001) /*!< FLASH Busy flag */ +#define FLASH_FLAG_EOP ((uint32_t)0x00000020) /*!< FLASH End of Operation flag */ +#define FLASH_FLAG_PGERR ((uint32_t)0x00000004) /*!< FLASH Program error flag */ +#define FLASH_FLAG_WRPRTERR ((uint32_t)0x00000010) /*!< FLASH Write protected error flag */ +#define FLASH_FLAG_OPTERR ((uint32_t)0x00000001) /*!< FLASH Option Byte error flag */ + +#define FLASH_FLAG_BANK1_BSY FLASH_FLAG_BSY /*!< FLASH BANK1 Busy flag*/ +#define FLASH_FLAG_BANK1_EOP FLASH_FLAG_EOP /*!< FLASH BANK1 End of Operation flag */ +#define FLASH_FLAG_BANK1_PGERR FLASH_FLAG_PGERR /*!< FLASH BANK1 Program error flag */ +#define FLASH_FLAG_BANK1_WRPRTERR FLASH_FLAG_WRPRTERR /*!< FLASH BANK1 Write protected error flag */ + +#define IS_FLASH_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFCA) == 0x00000000) && ((FLAG) != 0x00000000)) +#define IS_FLASH_GET_FLAG(FLAG) (((FLAG) == FLASH_FLAG_BSY) || ((FLAG) == FLASH_FLAG_EOP) || \ + ((FLAG) == FLASH_FLAG_PGERR) || ((FLAG) == FLASH_FLAG_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_BANK1_BSY) || ((FLAG) == FLASH_FLAG_BANK1_EOP) || \ + ((FLAG) == FLASH_FLAG_BANK1_PGERR) || ((FLAG) == FLASH_FLAG_BANK1_WRPRTERR) || \ + ((FLAG) == FLASH_FLAG_OPTERR)) +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Exported_Functions + * @{ + */ + +/*------------ Functions used for all STM32F10x devices -----*/ +void FLASH_SetLatency(uint32_t FLASH_Latency); +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess); +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer); +void FLASH_Unlock(void); +void FLASH_Lock(void); +FLASH_Status FLASH_ErasePage(uint32_t Page_Address); +FLASH_Status FLASH_EraseAllPages(void); +FLASH_Status FLASH_EraseOptionBytes(void); +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data); +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data); +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data); +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages); +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState); +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY); +uint32_t FLASH_GetUserOptionByte(void); +uint32_t FLASH_GetWriteProtectionOptionByte(void); +FlagStatus FLASH_GetReadOutProtectionStatus(void); +FlagStatus FLASH_GetPrefetchBufferStatus(void); +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState); +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG); +void FLASH_ClearFlag(uint32_t FLASH_FLAG); +FLASH_Status FLASH_GetStatus(void); +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout); + +/*------------ New function used for all STM32F10x devices -----*/ +void FLASH_UnlockBank1(void); +void FLASH_LockBank1(void); +FLASH_Status FLASH_EraseAllBank1Pages(void); +FLASH_Status FLASH_GetBank1Status(void); +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout); + +#ifdef STM32F10X_XL +/*---- New Functions used only with STM32F10x_XL density devices -----*/ +void FLASH_UnlockBank2(void); +void FLASH_LockBank2(void); +FLASH_Status FLASH_EraseAllBank2Pages(void); +FLASH_Status FLASH_GetBank2Status(void); +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout); +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT); +#endif + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_FLASH_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h new file mode 100755 index 0000000000..ee707e7439 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_fsmc.h @@ -0,0 +1,733 @@ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the FSMC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_FSMC_H +#define __STM32F10x_FSMC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup FSMC + * @{ + */ + +/** @defgroup FSMC_Exported_Types + * @{ + */ + +/** + * @brief Timing parameters For NOR/SRAM Banks + */ + +typedef struct +{ + uint32_t FSMC_AddressSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address setup time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories. */ + + uint32_t FSMC_AddressHoldTime; /*!< Defines the number of HCLK cycles to configure + the duration of the address hold time. + This parameter can be a value between 0 and 0xF. + @note: It is not used with synchronous NOR Flash memories.*/ + + uint32_t FSMC_DataSetupTime; /*!< Defines the number of HCLK cycles to configure + the duration of the data setup time. + This parameter can be a value between 0 and 0xFF. + @note: It is used for SRAMs, ROMs and asynchronous multiplexed NOR Flash memories. */ + + uint32_t FSMC_BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure + the duration of the bus turnaround. + This parameter can be a value between 0 and 0xF. + @note: It is only used for multiplexed NOR Flash memories. */ + + uint32_t FSMC_CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of HCLK cycles. + This parameter can be a value between 1 and 0xF. + @note: This parameter is not used for asynchronous NOR Flash, SRAM or ROM accesses. */ + + uint32_t FSMC_DataLatency; /*!< Defines the number of memory clock cycles to issue + to the memory before getting the first data. + The value of this parameter depends on the memory type as shown below: + - It must be set to 0 in case of a CRAM + - It is don't care in asynchronous NOR, SRAM or ROM accesses + - It may assume a value between 0 and 0xF in NOR Flash memories + with synchronous burst mode enable */ + + uint32_t FSMC_AccessMode; /*!< Specifies the asynchronous access mode. + This parameter can be a value of @ref FSMC_Access_Mode */ +}FSMC_NORSRAMTimingInitTypeDef; + +/** + * @brief FSMC NOR/SRAM Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NOR/SRAM memory bank that will be used. + This parameter can be a value of @ref FSMC_NORSRAM_Bank */ + + uint32_t FSMC_DataAddressMux; /*!< Specifies whether the address and data values are + multiplexed on the databus or not. + This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ + + uint32_t FSMC_MemoryType; /*!< Specifies the type of external memory attached to + the corresponding memory bank. + This parameter can be a value of @ref FSMC_Memory_Type */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be a value of @ref FSMC_Data_Width */ + + uint32_t FSMC_BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, + valid only with synchronous burst Flash memories. + This parameter can be a value of @ref FSMC_Burst_Access_Mode */ + + uint32_t FSMC_AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, + valid only with asynchronous Flash memories. + This parameter can be a value of @ref FSMC_AsynchronousWait */ + + uint32_t FSMC_WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing + the Flash memory in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ + + uint32_t FSMC_WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash + memory, valid only when accessing Flash memories in burst mode. + This parameter can be a value of @ref FSMC_Wrap_Mode */ + + uint32_t FSMC_WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one + clock cycle before the wait state or during the wait state, + valid only when accessing memories in burst mode. + This parameter can be a value of @ref FSMC_Wait_Timing */ + + uint32_t FSMC_WriteOperation; /*!< Enables or disables the write operation in the selected bank by the FSMC. + This parameter can be a value of @ref FSMC_Write_Operation */ + + uint32_t FSMC_WaitSignal; /*!< Enables or disables the wait-state insertion via wait + signal, valid for Flash memory access in burst mode. + This parameter can be a value of @ref FSMC_Wait_Signal */ + + uint32_t FSMC_ExtendedMode; /*!< Enables or disables the extended mode. + This parameter can be a value of @ref FSMC_Extended_Mode */ + + uint32_t FSMC_WriteBurst; /*!< Enables or disables the write burst operation. + This parameter can be a value of @ref FSMC_Write_Burst */ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_ReadWriteTimingStruct; /*!< Timing Parameters for write and read access if the ExtendedMode is not used*/ + + FSMC_NORSRAMTimingInitTypeDef* FSMC_WriteTimingStruct; /*!< Timing Parameters for write access if the ExtendedMode is used*/ +}FSMC_NORSRAMInitTypeDef; + +/** + * @brief Timing parameters For FSMC NAND and PCCARD Banks + */ + +typedef struct +{ + uint32_t FSMC_SetupTime; /*!< Defines the number of HCLK cycles to setup address before + the command assertion for NAND-Flash read or write access + to common/Attribute or I/O memory space (depending on + the memory space timing to be configured). + This parameter can be a value between 0 and 0xFF.*/ + + uint32_t FSMC_WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the + command for NAND-Flash read or write access to + common/Attribute or I/O memory space (depending on the + memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address + (and data for write access) after the command deassertion + for NAND-Flash read or write access to common/Attribute + or I/O memory space (depending on the memory space timing + to be configured). + This parameter can be a number between 0x00 and 0xFF */ + + uint32_t FSMC_HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the + databus is kept in HiZ after the start of a NAND-Flash + write access to common/Attribute or I/O memory space (depending + on the memory space timing to be configured). + This parameter can be a number between 0x00 and 0xFF */ +}FSMC_NAND_PCCARDTimingInitTypeDef; + +/** + * @brief FSMC NAND Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Bank; /*!< Specifies the NAND memory bank that will be used. + This parameter can be a value of @ref FSMC_NAND_Bank */ + + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_MemoryDataWidth; /*!< Specifies the external memory device width. + This parameter can be any value of @ref FSMC_Data_Width */ + + uint32_t FSMC_ECC; /*!< Enables or disables the ECC computation. + This parameter can be any value of @ref FSMC_ECC */ + + uint32_t FSMC_ECCPageSize; /*!< Defines the page size for the extended ECC. + This parameter can be any value of @ref FSMC_ECC_Page_Size */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ +}FSMC_NANDInitTypeDef; + +/** + * @brief FSMC PCCARD Init structure definition + */ + +typedef struct +{ + uint32_t FSMC_Waitfeature; /*!< Enables or disables the Wait feature for the Memory Bank. + This parameter can be any value of @ref FSMC_Wait_feature */ + + uint32_t FSMC_TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between CLE low and RE low. + This parameter can be a value between 0 and 0xFF. */ + + uint32_t FSMC_TARSetupTime; /*!< Defines the number of HCLK cycles to configure the + delay between ALE low and RE low. + This parameter can be a number between 0x0 and 0xFF */ + + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_CommonSpaceTimingStruct; /*!< FSMC Common Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_AttributeSpaceTimingStruct; /*!< FSMC Attribute Space Timing */ + + FSMC_NAND_PCCARDTimingInitTypeDef* FSMC_IOSpaceTimingStruct; /*!< FSMC IO Space Timing */ +}FSMC_PCCARDInitTypeDef; + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Constants + * @{ + */ + +/** @defgroup FSMC_NORSRAM_Bank + * @{ + */ +#define FSMC_Bank1_NORSRAM1 ((uint32_t)0x00000000) +#define FSMC_Bank1_NORSRAM2 ((uint32_t)0x00000002) +#define FSMC_Bank1_NORSRAM3 ((uint32_t)0x00000004) +#define FSMC_Bank1_NORSRAM4 ((uint32_t)0x00000006) +/** + * @} + */ + +/** @defgroup FSMC_NAND_Bank + * @{ + */ +#define FSMC_Bank2_NAND ((uint32_t)0x00000010) +#define FSMC_Bank3_NAND ((uint32_t)0x00000100) +/** + * @} + */ + +/** @defgroup FSMC_PCCARD_Bank + * @{ + */ +#define FSMC_Bank4_PCCARD ((uint32_t)0x00001000) +/** + * @} + */ + +#define IS_FSMC_NORSRAM_BANK(BANK) (((BANK) == FSMC_Bank1_NORSRAM1) || \ + ((BANK) == FSMC_Bank1_NORSRAM2) || \ + ((BANK) == FSMC_Bank1_NORSRAM3) || \ + ((BANK) == FSMC_Bank1_NORSRAM4)) + +#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND)) + +#define IS_FSMC_GETFLAG_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +#define IS_FSMC_IT_BANK(BANK) (((BANK) == FSMC_Bank2_NAND) || \ + ((BANK) == FSMC_Bank3_NAND) || \ + ((BANK) == FSMC_Bank4_PCCARD)) + +/** @defgroup NOR_SRAM_Controller + * @{ + */ + +/** @defgroup FSMC_Data_Address_Bus_Multiplexing + * @{ + */ + +#define FSMC_DataAddressMux_Disable ((uint32_t)0x00000000) +#define FSMC_DataAddressMux_Enable ((uint32_t)0x00000002) +#define IS_FSMC_MUX(MUX) (((MUX) == FSMC_DataAddressMux_Disable) || \ + ((MUX) == FSMC_DataAddressMux_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Memory_Type + * @{ + */ + +#define FSMC_MemoryType_SRAM ((uint32_t)0x00000000) +#define FSMC_MemoryType_PSRAM ((uint32_t)0x00000004) +#define FSMC_MemoryType_NOR ((uint32_t)0x00000008) +#define IS_FSMC_MEMORY(MEMORY) (((MEMORY) == FSMC_MemoryType_SRAM) || \ + ((MEMORY) == FSMC_MemoryType_PSRAM)|| \ + ((MEMORY) == FSMC_MemoryType_NOR)) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Width + * @{ + */ + +#define FSMC_MemoryDataWidth_8b ((uint32_t)0x00000000) +#define FSMC_MemoryDataWidth_16b ((uint32_t)0x00000010) +#define IS_FSMC_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_MemoryDataWidth_8b) || \ + ((WIDTH) == FSMC_MemoryDataWidth_16b)) + +/** + * @} + */ + +/** @defgroup FSMC_Burst_Access_Mode + * @{ + */ + +#define FSMC_BurstAccessMode_Disable ((uint32_t)0x00000000) +#define FSMC_BurstAccessMode_Enable ((uint32_t)0x00000100) +#define IS_FSMC_BURSTMODE(STATE) (((STATE) == FSMC_BurstAccessMode_Disable) || \ + ((STATE) == FSMC_BurstAccessMode_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_AsynchronousWait + * @{ + */ +#define FSMC_AsynchronousWait_Disable ((uint32_t)0x00000000) +#define FSMC_AsynchronousWait_Enable ((uint32_t)0x00008000) +#define IS_FSMC_ASYNWAIT(STATE) (((STATE) == FSMC_AsynchronousWait_Disable) || \ + ((STATE) == FSMC_AsynchronousWait_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal_Polarity + * @{ + */ + +#define FSMC_WaitSignalPolarity_Low ((uint32_t)0x00000000) +#define FSMC_WaitSignalPolarity_High ((uint32_t)0x00000200) +#define IS_FSMC_WAIT_POLARITY(POLARITY) (((POLARITY) == FSMC_WaitSignalPolarity_Low) || \ + ((POLARITY) == FSMC_WaitSignalPolarity_High)) + +/** + * @} + */ + +/** @defgroup FSMC_Wrap_Mode + * @{ + */ + +#define FSMC_WrapMode_Disable ((uint32_t)0x00000000) +#define FSMC_WrapMode_Enable ((uint32_t)0x00000400) +#define IS_FSMC_WRAP_MODE(MODE) (((MODE) == FSMC_WrapMode_Disable) || \ + ((MODE) == FSMC_WrapMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Timing + * @{ + */ + +#define FSMC_WaitSignalActive_BeforeWaitState ((uint32_t)0x00000000) +#define FSMC_WaitSignalActive_DuringWaitState ((uint32_t)0x00000800) +#define IS_FSMC_WAIT_SIGNAL_ACTIVE(ACTIVE) (((ACTIVE) == FSMC_WaitSignalActive_BeforeWaitState) || \ + ((ACTIVE) == FSMC_WaitSignalActive_DuringWaitState)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Operation + * @{ + */ + +#define FSMC_WriteOperation_Disable ((uint32_t)0x00000000) +#define FSMC_WriteOperation_Enable ((uint32_t)0x00001000) +#define IS_FSMC_WRITE_OPERATION(OPERATION) (((OPERATION) == FSMC_WriteOperation_Disable) || \ + ((OPERATION) == FSMC_WriteOperation_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Signal + * @{ + */ + +#define FSMC_WaitSignal_Disable ((uint32_t)0x00000000) +#define FSMC_WaitSignal_Enable ((uint32_t)0x00002000) +#define IS_FSMC_WAITE_SIGNAL(SIGNAL) (((SIGNAL) == FSMC_WaitSignal_Disable) || \ + ((SIGNAL) == FSMC_WaitSignal_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Extended_Mode + * @{ + */ + +#define FSMC_ExtendedMode_Disable ((uint32_t)0x00000000) +#define FSMC_ExtendedMode_Enable ((uint32_t)0x00004000) + +#define IS_FSMC_EXTENDED_MODE(MODE) (((MODE) == FSMC_ExtendedMode_Disable) || \ + ((MODE) == FSMC_ExtendedMode_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_Write_Burst + * @{ + */ + +#define FSMC_WriteBurst_Disable ((uint32_t)0x00000000) +#define FSMC_WriteBurst_Enable ((uint32_t)0x00080000) +#define IS_FSMC_WRITE_BURST(BURST) (((BURST) == FSMC_WriteBurst_Disable) || \ + ((BURST) == FSMC_WriteBurst_Enable)) +/** + * @} + */ + +/** @defgroup FSMC_Address_Setup_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_SETUP_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Address_Hold_Time + * @{ + */ + +#define IS_FSMC_ADDRESS_HOLD_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Setup_Time + * @{ + */ + +#define IS_FSMC_DATASETUP_TIME(TIME) (((TIME) > 0) && ((TIME) <= 0xFF)) + +/** + * @} + */ + +/** @defgroup FSMC_Bus_Turn_around_Duration + * @{ + */ + +#define IS_FSMC_TURNAROUND_TIME(TIME) ((TIME) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_CLK_Division + * @{ + */ + +#define IS_FSMC_CLK_DIV(DIV) ((DIV) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Data_Latency + * @{ + */ + +#define IS_FSMC_DATA_LATENCY(LATENCY) ((LATENCY) <= 0xF) + +/** + * @} + */ + +/** @defgroup FSMC_Access_Mode + * @{ + */ + +#define FSMC_AccessMode_A ((uint32_t)0x00000000) +#define FSMC_AccessMode_B ((uint32_t)0x10000000) +#define FSMC_AccessMode_C ((uint32_t)0x20000000) +#define FSMC_AccessMode_D ((uint32_t)0x30000000) +#define IS_FSMC_ACCESS_MODE(MODE) (((MODE) == FSMC_AccessMode_A) || \ + ((MODE) == FSMC_AccessMode_B) || \ + ((MODE) == FSMC_AccessMode_C) || \ + ((MODE) == FSMC_AccessMode_D)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup NAND_PCCARD_Controller + * @{ + */ + +/** @defgroup FSMC_Wait_feature + * @{ + */ + +#define FSMC_Waitfeature_Disable ((uint32_t)0x00000000) +#define FSMC_Waitfeature_Enable ((uint32_t)0x00000002) +#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_Waitfeature_Disable) || \ + ((FEATURE) == FSMC_Waitfeature_Enable)) + +/** + * @} + */ + + +/** @defgroup FSMC_ECC + * @{ + */ + +#define FSMC_ECC_Disable ((uint32_t)0x00000000) +#define FSMC_ECC_Enable ((uint32_t)0x00000040) +#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_ECC_Disable) || \ + ((STATE) == FSMC_ECC_Enable)) + +/** + * @} + */ + +/** @defgroup FSMC_ECC_Page_Size + * @{ + */ + +#define FSMC_ECCPageSize_256Bytes ((uint32_t)0x00000000) +#define FSMC_ECCPageSize_512Bytes ((uint32_t)0x00020000) +#define FSMC_ECCPageSize_1024Bytes ((uint32_t)0x00040000) +#define FSMC_ECCPageSize_2048Bytes ((uint32_t)0x00060000) +#define FSMC_ECCPageSize_4096Bytes ((uint32_t)0x00080000) +#define FSMC_ECCPageSize_8192Bytes ((uint32_t)0x000A0000) +#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_ECCPageSize_256Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_512Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_1024Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_2048Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_4096Bytes) || \ + ((SIZE) == FSMC_ECCPageSize_8192Bytes)) + +/** + * @} + */ + +/** @defgroup FSMC_TCLR_Setup_Time + * @{ + */ + +#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_TAR_Setup_Time + * @{ + */ + +#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Setup_Time + * @{ + */ + +#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Wait_Setup_Time + * @{ + */ + +#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Hold_Setup_Time + * @{ + */ + +#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_HiZ_Setup_Time + * @{ + */ + +#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 0xFF) + +/** + * @} + */ + +/** @defgroup FSMC_Interrupt_sources + * @{ + */ + +#define FSMC_IT_RisingEdge ((uint32_t)0x00000008) +#define FSMC_IT_Level ((uint32_t)0x00000010) +#define FSMC_IT_FallingEdge ((uint32_t)0x00000020) +#define IS_FSMC_IT(IT) ((((IT) & (uint32_t)0xFFFFFFC7) == 0x00000000) && ((IT) != 0x00000000)) +#define IS_FSMC_GET_IT(IT) (((IT) == FSMC_IT_RisingEdge) || \ + ((IT) == FSMC_IT_Level) || \ + ((IT) == FSMC_IT_FallingEdge)) +/** + * @} + */ + +/** @defgroup FSMC_Flags + * @{ + */ + +#define FSMC_FLAG_RisingEdge ((uint32_t)0x00000001) +#define FSMC_FLAG_Level ((uint32_t)0x00000002) +#define FSMC_FLAG_FallingEdge ((uint32_t)0x00000004) +#define FSMC_FLAG_FEMPT ((uint32_t)0x00000040) +#define IS_FSMC_GET_FLAG(FLAG) (((FLAG) == FSMC_FLAG_RisingEdge) || \ + ((FLAG) == FSMC_FLAG_Level) || \ + ((FLAG) == FSMC_FLAG_FallingEdge) || \ + ((FLAG) == FSMC_FLAG_FEMPT)) + +#define IS_FSMC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFFFFFFF8) == 0x00000000) && ((FLAG) != 0x00000000)) + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Exported_Functions + * @{ + */ + +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank); +void FSMC_NANDDeInit(uint32_t FSMC_Bank); +void FSMC_PCCARDDeInit(void); +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct); +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct); +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct); +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState); +void FSMC_PCCARDCmd(FunctionalState NewState); +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState); +uint32_t FSMC_GetECC(uint32_t FSMC_Bank); +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState); +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG); +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT); +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_FSMC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h new file mode 100755 index 0000000000..b8aa49a2a8 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_gpio.h @@ -0,0 +1,385 @@ +/** + ****************************************************************************** + * @file stm32f10x_gpio.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the GPIO + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_GPIO_H +#define __STM32F10x_GPIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup GPIO + * @{ + */ + +/** @defgroup GPIO_Exported_Types + * @{ + */ + +#define IS_GPIO_ALL_PERIPH(PERIPH) (((PERIPH) == GPIOA) || \ + ((PERIPH) == GPIOB) || \ + ((PERIPH) == GPIOC) || \ + ((PERIPH) == GPIOD) || \ + ((PERIPH) == GPIOE) || \ + ((PERIPH) == GPIOF) || \ + ((PERIPH) == GPIOG)) + +/** + * @brief Output Maximum frequency selection + */ + +typedef enum +{ + GPIO_Speed_10MHz = 1, + GPIO_Speed_2MHz, + GPIO_Speed_50MHz +}GPIOSpeed_TypeDef; +#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_Speed_10MHz) || ((SPEED) == GPIO_Speed_2MHz) || \ + ((SPEED) == GPIO_Speed_50MHz)) + +/** + * @brief Configuration Mode enumeration + */ + +typedef enum +{ GPIO_Mode_AIN = 0x0, + GPIO_Mode_IN_FLOATING = 0x04, + GPIO_Mode_IPD = 0x28, + GPIO_Mode_IPU = 0x48, + GPIO_Mode_Out_OD = 0x14, + GPIO_Mode_Out_PP = 0x10, + GPIO_Mode_AF_OD = 0x1C, + GPIO_Mode_AF_PP = 0x18 +}GPIOMode_TypeDef; + +#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_Mode_AIN) || ((MODE) == GPIO_Mode_IN_FLOATING) || \ + ((MODE) == GPIO_Mode_IPD) || ((MODE) == GPIO_Mode_IPU) || \ + ((MODE) == GPIO_Mode_Out_OD) || ((MODE) == GPIO_Mode_Out_PP) || \ + ((MODE) == GPIO_Mode_AF_OD) || ((MODE) == GPIO_Mode_AF_PP)) + +/** + * @brief GPIO Init structure definition + */ + +typedef struct +{ + uint16_t GPIO_Pin; /*!< Specifies the GPIO pins to be configured. + This parameter can be any value of @ref GPIO_pins_define */ + + GPIOSpeed_TypeDef GPIO_Speed; /*!< Specifies the speed for the selected pins. + This parameter can be a value of @ref GPIOSpeed_TypeDef */ + + GPIOMode_TypeDef GPIO_Mode; /*!< Specifies the operating mode for the selected pins. + This parameter can be a value of @ref GPIOMode_TypeDef */ +}GPIO_InitTypeDef; + + +/** + * @brief Bit_SET and Bit_RESET enumeration + */ + +typedef enum +{ Bit_RESET = 0, + Bit_SET +}BitAction; + +#define IS_GPIO_BIT_ACTION(ACTION) (((ACTION) == Bit_RESET) || ((ACTION) == Bit_SET)) + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Constants + * @{ + */ + +/** @defgroup GPIO_pins_define + * @{ + */ + +#define GPIO_Pin_0 ((uint16_t)0x0001) /*!< Pin 0 selected */ +#define GPIO_Pin_1 ((uint16_t)0x0002) /*!< Pin 1 selected */ +#define GPIO_Pin_2 ((uint16_t)0x0004) /*!< Pin 2 selected */ +#define GPIO_Pin_3 ((uint16_t)0x0008) /*!< Pin 3 selected */ +#define GPIO_Pin_4 ((uint16_t)0x0010) /*!< Pin 4 selected */ +#define GPIO_Pin_5 ((uint16_t)0x0020) /*!< Pin 5 selected */ +#define GPIO_Pin_6 ((uint16_t)0x0040) /*!< Pin 6 selected */ +#define GPIO_Pin_7 ((uint16_t)0x0080) /*!< Pin 7 selected */ +#define GPIO_Pin_8 ((uint16_t)0x0100) /*!< Pin 8 selected */ +#define GPIO_Pin_9 ((uint16_t)0x0200) /*!< Pin 9 selected */ +#define GPIO_Pin_10 ((uint16_t)0x0400) /*!< Pin 10 selected */ +#define GPIO_Pin_11 ((uint16_t)0x0800) /*!< Pin 11 selected */ +#define GPIO_Pin_12 ((uint16_t)0x1000) /*!< Pin 12 selected */ +#define GPIO_Pin_13 ((uint16_t)0x2000) /*!< Pin 13 selected */ +#define GPIO_Pin_14 ((uint16_t)0x4000) /*!< Pin 14 selected */ +#define GPIO_Pin_15 ((uint16_t)0x8000) /*!< Pin 15 selected */ +#define GPIO_Pin_All ((uint16_t)0xFFFF) /*!< All pins selected */ + +#define IS_GPIO_PIN(PIN) ((((PIN) & (uint16_t)0x00) == 0x00) && ((PIN) != (uint16_t)0x00)) + +#define IS_GET_GPIO_PIN(PIN) (((PIN) == GPIO_Pin_0) || \ + ((PIN) == GPIO_Pin_1) || \ + ((PIN) == GPIO_Pin_2) || \ + ((PIN) == GPIO_Pin_3) || \ + ((PIN) == GPIO_Pin_4) || \ + ((PIN) == GPIO_Pin_5) || \ + ((PIN) == GPIO_Pin_6) || \ + ((PIN) == GPIO_Pin_7) || \ + ((PIN) == GPIO_Pin_8) || \ + ((PIN) == GPIO_Pin_9) || \ + ((PIN) == GPIO_Pin_10) || \ + ((PIN) == GPIO_Pin_11) || \ + ((PIN) == GPIO_Pin_12) || \ + ((PIN) == GPIO_Pin_13) || \ + ((PIN) == GPIO_Pin_14) || \ + ((PIN) == GPIO_Pin_15)) + +/** + * @} + */ + +/** @defgroup GPIO_Remap_define + * @{ + */ + +#define GPIO_Remap_SPI1 ((uint32_t)0x00000001) /*!< SPI1 Alternate Function mapping */ +#define GPIO_Remap_I2C1 ((uint32_t)0x00000002) /*!< I2C1 Alternate Function mapping */ +#define GPIO_Remap_USART1 ((uint32_t)0x00000004) /*!< USART1 Alternate Function mapping */ +#define GPIO_Remap_USART2 ((uint32_t)0x00000008) /*!< USART2 Alternate Function mapping */ +#define GPIO_PartialRemap_USART3 ((uint32_t)0x00140010) /*!< USART3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_USART3 ((uint32_t)0x00140030) /*!< USART3 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM1 ((uint32_t)0x00160040) /*!< TIM1 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM1 ((uint32_t)0x001600C0) /*!< TIM1 Full Alternate Function mapping */ +#define GPIO_PartialRemap1_TIM2 ((uint32_t)0x00180100) /*!< TIM2 Partial1 Alternate Function mapping */ +#define GPIO_PartialRemap2_TIM2 ((uint32_t)0x00180200) /*!< TIM2 Partial2 Alternate Function mapping */ +#define GPIO_FullRemap_TIM2 ((uint32_t)0x00180300) /*!< TIM2 Full Alternate Function mapping */ +#define GPIO_PartialRemap_TIM3 ((uint32_t)0x001A0800) /*!< TIM3 Partial Alternate Function mapping */ +#define GPIO_FullRemap_TIM3 ((uint32_t)0x001A0C00) /*!< TIM3 Full Alternate Function mapping */ +#define GPIO_Remap_TIM4 ((uint32_t)0x00001000) /*!< TIM4 Alternate Function mapping */ +#define GPIO_Remap1_CAN1 ((uint32_t)0x001D4000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap2_CAN1 ((uint32_t)0x001D6000) /*!< CAN1 Alternate Function mapping */ +#define GPIO_Remap_PD01 ((uint32_t)0x00008000) /*!< PD01 Alternate Function mapping */ +#define GPIO_Remap_TIM5CH4_LSI ((uint32_t)0x00200001) /*!< LSI connected to TIM5 Channel4 input capture for calibration */ +#define GPIO_Remap_ADC1_ETRGINJ ((uint32_t)0x00200002) /*!< ADC1 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC1_ETRGREG ((uint32_t)0x00200004) /*!< ADC1 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGINJ ((uint32_t)0x00200008) /*!< ADC2 External Trigger Injected Conversion remapping */ +#define GPIO_Remap_ADC2_ETRGREG ((uint32_t)0x00200010) /*!< ADC2 External Trigger Regular Conversion remapping */ +#define GPIO_Remap_ETH ((uint32_t)0x00200020) /*!< Ethernet remapping (only for Connectivity line devices) */ +#define GPIO_Remap_CAN2 ((uint32_t)0x00200040) /*!< CAN2 remapping (only for Connectivity line devices) */ +#define GPIO_Remap_SWJ_NoJTRST ((uint32_t)0x00300100) /*!< Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST */ +#define GPIO_Remap_SWJ_JTAGDisable ((uint32_t)0x00300200) /*!< JTAG-DP Disabled and SW-DP Enabled */ +#define GPIO_Remap_SWJ_Disable ((uint32_t)0x00300400) /*!< Full SWJ Disabled (JTAG-DP + SW-DP) */ +#define GPIO_Remap_SPI3 ((uint32_t)0x00201100) /*!< SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) */ +#define GPIO_Remap_TIM2ITR1_PTP_SOF ((uint32_t)0x00202000) /*!< Ethernet PTP output or USB OTG SOF (Start of Frame) connected + to TIM2 Internal Trigger 1 for calibration + (only for Connectivity line devices) */ +#define GPIO_Remap_PTP_PPS ((uint32_t)0x00204000) /*!< Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) */ + +#define GPIO_Remap_TIM15 ((uint32_t)0x80000001) /*!< TIM15 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM16 ((uint32_t)0x80000002) /*!< TIM16 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM17 ((uint32_t)0x80000004) /*!< TIM17 Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_CEC ((uint32_t)0x80000008) /*!< CEC Alternate Function mapping (only for Value line devices) */ +#define GPIO_Remap_TIM1_DMA ((uint32_t)0x80000010) /*!< TIM1 DMA requests mapping (only for Value line devices) */ + +#define GPIO_Remap_TIM9 ((uint32_t)0x80000020) /*!< TIM9 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM10 ((uint32_t)0x80000040) /*!< TIM10 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM11 ((uint32_t)0x80000080) /*!< TIM11 Alternate Function mapping (only for XL-density devices) */ +#define GPIO_Remap_TIM13 ((uint32_t)0x80000100) /*!< TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_TIM14 ((uint32_t)0x80000200) /*!< TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) */ +#define GPIO_Remap_FSMC_NADV ((uint32_t)0x80000400) /*!< FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) */ + +#define GPIO_Remap_TIM67_DAC_DMA ((uint32_t)0x80000800) /*!< TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) */ +#define GPIO_Remap_TIM12 ((uint32_t)0x80001000) /*!< TIM12 Alternate Function mapping (only for High density Value line devices) */ +#define GPIO_Remap_MISC ((uint32_t)0x80002000) /*!< Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + only for High density Value line devices) */ + +#define IS_GPIO_REMAP(REMAP) (((REMAP) == GPIO_Remap_SPI1) || ((REMAP) == GPIO_Remap_I2C1) || \ + ((REMAP) == GPIO_Remap_USART1) || ((REMAP) == GPIO_Remap_USART2) || \ + ((REMAP) == GPIO_PartialRemap_USART3) || ((REMAP) == GPIO_FullRemap_USART3) || \ + ((REMAP) == GPIO_PartialRemap_TIM1) || ((REMAP) == GPIO_FullRemap_TIM1) || \ + ((REMAP) == GPIO_PartialRemap1_TIM2) || ((REMAP) == GPIO_PartialRemap2_TIM2) || \ + ((REMAP) == GPIO_FullRemap_TIM2) || ((REMAP) == GPIO_PartialRemap_TIM3) || \ + ((REMAP) == GPIO_FullRemap_TIM3) || ((REMAP) == GPIO_Remap_TIM4) || \ + ((REMAP) == GPIO_Remap1_CAN1) || ((REMAP) == GPIO_Remap2_CAN1) || \ + ((REMAP) == GPIO_Remap_PD01) || ((REMAP) == GPIO_Remap_TIM5CH4_LSI) || \ + ((REMAP) == GPIO_Remap_ADC1_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC1_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ADC2_ETRGINJ) ||((REMAP) == GPIO_Remap_ADC2_ETRGREG) || \ + ((REMAP) == GPIO_Remap_ETH) ||((REMAP) == GPIO_Remap_CAN2) || \ + ((REMAP) == GPIO_Remap_SWJ_NoJTRST) || ((REMAP) == GPIO_Remap_SWJ_JTAGDisable) || \ + ((REMAP) == GPIO_Remap_SWJ_Disable)|| ((REMAP) == GPIO_Remap_SPI3) || \ + ((REMAP) == GPIO_Remap_TIM2ITR1_PTP_SOF) || ((REMAP) == GPIO_Remap_PTP_PPS) || \ + ((REMAP) == GPIO_Remap_TIM15) || ((REMAP) == GPIO_Remap_TIM16) || \ + ((REMAP) == GPIO_Remap_TIM17) || ((REMAP) == GPIO_Remap_CEC) || \ + ((REMAP) == GPIO_Remap_TIM1_DMA) || ((REMAP) == GPIO_Remap_TIM9) || \ + ((REMAP) == GPIO_Remap_TIM10) || ((REMAP) == GPIO_Remap_TIM11) || \ + ((REMAP) == GPIO_Remap_TIM13) || ((REMAP) == GPIO_Remap_TIM14) || \ + ((REMAP) == GPIO_Remap_FSMC_NADV) || ((REMAP) == GPIO_Remap_TIM67_DAC_DMA) || \ + ((REMAP) == GPIO_Remap_TIM12) || ((REMAP) == GPIO_Remap_MISC)) + +/** + * @} + */ + +/** @defgroup GPIO_Port_Sources + * @{ + */ + +#define GPIO_PortSourceGPIOA ((uint8_t)0x00) +#define GPIO_PortSourceGPIOB ((uint8_t)0x01) +#define GPIO_PortSourceGPIOC ((uint8_t)0x02) +#define GPIO_PortSourceGPIOD ((uint8_t)0x03) +#define GPIO_PortSourceGPIOE ((uint8_t)0x04) +#define GPIO_PortSourceGPIOF ((uint8_t)0x05) +#define GPIO_PortSourceGPIOG ((uint8_t)0x06) +#define IS_GPIO_EVENTOUT_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE)) + +#define IS_GPIO_EXTI_PORT_SOURCE(PORTSOURCE) (((PORTSOURCE) == GPIO_PortSourceGPIOA) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOB) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOC) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOD) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOE) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOF) || \ + ((PORTSOURCE) == GPIO_PortSourceGPIOG)) + +/** + * @} + */ + +/** @defgroup GPIO_Pin_sources + * @{ + */ + +#define GPIO_PinSource0 ((uint8_t)0x00) +#define GPIO_PinSource1 ((uint8_t)0x01) +#define GPIO_PinSource2 ((uint8_t)0x02) +#define GPIO_PinSource3 ((uint8_t)0x03) +#define GPIO_PinSource4 ((uint8_t)0x04) +#define GPIO_PinSource5 ((uint8_t)0x05) +#define GPIO_PinSource6 ((uint8_t)0x06) +#define GPIO_PinSource7 ((uint8_t)0x07) +#define GPIO_PinSource8 ((uint8_t)0x08) +#define GPIO_PinSource9 ((uint8_t)0x09) +#define GPIO_PinSource10 ((uint8_t)0x0A) +#define GPIO_PinSource11 ((uint8_t)0x0B) +#define GPIO_PinSource12 ((uint8_t)0x0C) +#define GPIO_PinSource13 ((uint8_t)0x0D) +#define GPIO_PinSource14 ((uint8_t)0x0E) +#define GPIO_PinSource15 ((uint8_t)0x0F) + +#define IS_GPIO_PIN_SOURCE(PINSOURCE) (((PINSOURCE) == GPIO_PinSource0) || \ + ((PINSOURCE) == GPIO_PinSource1) || \ + ((PINSOURCE) == GPIO_PinSource2) || \ + ((PINSOURCE) == GPIO_PinSource3) || \ + ((PINSOURCE) == GPIO_PinSource4) || \ + ((PINSOURCE) == GPIO_PinSource5) || \ + ((PINSOURCE) == GPIO_PinSource6) || \ + ((PINSOURCE) == GPIO_PinSource7) || \ + ((PINSOURCE) == GPIO_PinSource8) || \ + ((PINSOURCE) == GPIO_PinSource9) || \ + ((PINSOURCE) == GPIO_PinSource10) || \ + ((PINSOURCE) == GPIO_PinSource11) || \ + ((PINSOURCE) == GPIO_PinSource12) || \ + ((PINSOURCE) == GPIO_PinSource13) || \ + ((PINSOURCE) == GPIO_PinSource14) || \ + ((PINSOURCE) == GPIO_PinSource15)) + +/** + * @} + */ + +/** @defgroup Ethernet_Media_Interface + * @{ + */ +#define GPIO_ETH_MediaInterface_MII ((u32)0x00000000) +#define GPIO_ETH_MediaInterface_RMII ((u32)0x00000001) + +#define IS_GPIO_ETH_MEDIA_INTERFACE(INTERFACE) (((INTERFACE) == GPIO_ETH_MediaInterface_MII) || \ + ((INTERFACE) == GPIO_ETH_MediaInterface_RMII)) + +/** + * @} + */ +/** + * @} + */ + +/** @defgroup GPIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Exported_Functions + * @{ + */ + +void GPIO_DeInit(GPIO_TypeDef* GPIOx); +void GPIO_AFIODeInit(void); +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct); +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct); +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx); +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx); +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal); +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal); +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_EventOutputCmd(FunctionalState NewState); +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState); +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource); +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_GPIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h new file mode 100755 index 0000000000..2d42e5ce36 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_i2c.h @@ -0,0 +1,684 @@ +/** + ****************************************************************************** + * @file stm32f10x_i2c.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the I2C firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_I2C_H +#define __STM32F10x_I2C_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup I2C + * @{ + */ + +/** @defgroup I2C_Exported_Types + * @{ + */ + +/** + * @brief I2C Init structure definition + */ + +typedef struct +{ + uint32_t I2C_ClockSpeed; /*!< Specifies the clock frequency. + This parameter must be set to a value lower than 400kHz */ + + uint16_t I2C_Mode; /*!< Specifies the I2C mode. + This parameter can be a value of @ref I2C_mode */ + + uint16_t I2C_DutyCycle; /*!< Specifies the I2C fast mode duty cycle. + This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ + + uint16_t I2C_OwnAddress1; /*!< Specifies the first device own address. + This parameter can be a 7-bit or 10-bit address. */ + + uint16_t I2C_Ack; /*!< Enables or disables the acknowledgement. + This parameter can be a value of @ref I2C_acknowledgement */ + + uint16_t I2C_AcknowledgedAddress; /*!< Specifies if 7-bit or 10-bit address is acknowledged. + This parameter can be a value of @ref I2C_acknowledged_address */ +}I2C_InitTypeDef; + +/** + * @} + */ + + +/** @defgroup I2C_Exported_Constants + * @{ + */ + +#define IS_I2C_ALL_PERIPH(PERIPH) (((PERIPH) == I2C1) || \ + ((PERIPH) == I2C2)) +/** @defgroup I2C_mode + * @{ + */ + +#define I2C_Mode_I2C ((uint16_t)0x0000) +#define I2C_Mode_SMBusDevice ((uint16_t)0x0002) +#define I2C_Mode_SMBusHost ((uint16_t)0x000A) +#define IS_I2C_MODE(MODE) (((MODE) == I2C_Mode_I2C) || \ + ((MODE) == I2C_Mode_SMBusDevice) || \ + ((MODE) == I2C_Mode_SMBusHost)) +/** + * @} + */ + +/** @defgroup I2C_duty_cycle_in_fast_mode + * @{ + */ + +#define I2C_DutyCycle_16_9 ((uint16_t)0x4000) /*!< I2C fast mode Tlow/Thigh = 16/9 */ +#define I2C_DutyCycle_2 ((uint16_t)0xBFFF) /*!< I2C fast mode Tlow/Thigh = 2 */ +#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DutyCycle_16_9) || \ + ((CYCLE) == I2C_DutyCycle_2)) +/** + * @} + */ + +/** @defgroup I2C_acknowledgement + * @{ + */ + +#define I2C_Ack_Enable ((uint16_t)0x0400) +#define I2C_Ack_Disable ((uint16_t)0x0000) +#define IS_I2C_ACK_STATE(STATE) (((STATE) == I2C_Ack_Enable) || \ + ((STATE) == I2C_Ack_Disable)) +/** + * @} + */ + +/** @defgroup I2C_transfer_direction + * @{ + */ + +#define I2C_Direction_Transmitter ((uint8_t)0x00) +#define I2C_Direction_Receiver ((uint8_t)0x01) +#define IS_I2C_DIRECTION(DIRECTION) (((DIRECTION) == I2C_Direction_Transmitter) || \ + ((DIRECTION) == I2C_Direction_Receiver)) +/** + * @} + */ + +/** @defgroup I2C_acknowledged_address + * @{ + */ + +#define I2C_AcknowledgedAddress_7bit ((uint16_t)0x4000) +#define I2C_AcknowledgedAddress_10bit ((uint16_t)0xC000) +#define IS_I2C_ACKNOWLEDGE_ADDRESS(ADDRESS) (((ADDRESS) == I2C_AcknowledgedAddress_7bit) || \ + ((ADDRESS) == I2C_AcknowledgedAddress_10bit)) +/** + * @} + */ + +/** @defgroup I2C_registers + * @{ + */ + +#define I2C_Register_CR1 ((uint8_t)0x00) +#define I2C_Register_CR2 ((uint8_t)0x04) +#define I2C_Register_OAR1 ((uint8_t)0x08) +#define I2C_Register_OAR2 ((uint8_t)0x0C) +#define I2C_Register_DR ((uint8_t)0x10) +#define I2C_Register_SR1 ((uint8_t)0x14) +#define I2C_Register_SR2 ((uint8_t)0x18) +#define I2C_Register_CCR ((uint8_t)0x1C) +#define I2C_Register_TRISE ((uint8_t)0x20) +#define IS_I2C_REGISTER(REGISTER) (((REGISTER) == I2C_Register_CR1) || \ + ((REGISTER) == I2C_Register_CR2) || \ + ((REGISTER) == I2C_Register_OAR1) || \ + ((REGISTER) == I2C_Register_OAR2) || \ + ((REGISTER) == I2C_Register_DR) || \ + ((REGISTER) == I2C_Register_SR1) || \ + ((REGISTER) == I2C_Register_SR2) || \ + ((REGISTER) == I2C_Register_CCR) || \ + ((REGISTER) == I2C_Register_TRISE)) +/** + * @} + */ + +/** @defgroup I2C_SMBus_alert_pin_level + * @{ + */ + +#define I2C_SMBusAlert_Low ((uint16_t)0x2000) +#define I2C_SMBusAlert_High ((uint16_t)0xDFFF) +#define IS_I2C_SMBUS_ALERT(ALERT) (((ALERT) == I2C_SMBusAlert_Low) || \ + ((ALERT) == I2C_SMBusAlert_High)) +/** + * @} + */ + +/** @defgroup I2C_PEC_position + * @{ + */ + +#define I2C_PECPosition_Next ((uint16_t)0x0800) +#define I2C_PECPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_PEC_POSITION(POSITION) (((POSITION) == I2C_PECPosition_Next) || \ + ((POSITION) == I2C_PECPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_NCAK_position + * @{ + */ + +#define I2C_NACKPosition_Next ((uint16_t)0x0800) +#define I2C_NACKPosition_Current ((uint16_t)0xF7FF) +#define IS_I2C_NACK_POSITION(POSITION) (((POSITION) == I2C_NACKPosition_Next) || \ + ((POSITION) == I2C_NACKPosition_Current)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_BUF ((uint16_t)0x0400) +#define I2C_IT_EVT ((uint16_t)0x0200) +#define I2C_IT_ERR ((uint16_t)0x0100) +#define IS_I2C_CONFIG_IT(IT) ((((IT) & (uint16_t)0xF8FF) == 0x00) && ((IT) != 0x00)) +/** + * @} + */ + +/** @defgroup I2C_interrupts_definition + * @{ + */ + +#define I2C_IT_SMBALERT ((uint32_t)0x01008000) +#define I2C_IT_TIMEOUT ((uint32_t)0x01004000) +#define I2C_IT_PECERR ((uint32_t)0x01001000) +#define I2C_IT_OVR ((uint32_t)0x01000800) +#define I2C_IT_AF ((uint32_t)0x01000400) +#define I2C_IT_ARLO ((uint32_t)0x01000200) +#define I2C_IT_BERR ((uint32_t)0x01000100) +#define I2C_IT_TXE ((uint32_t)0x06000080) +#define I2C_IT_RXNE ((uint32_t)0x06000040) +#define I2C_IT_STOPF ((uint32_t)0x02000010) +#define I2C_IT_ADD10 ((uint32_t)0x02000008) +#define I2C_IT_BTF ((uint32_t)0x02000004) +#define I2C_IT_ADDR ((uint32_t)0x02000002) +#define I2C_IT_SB ((uint32_t)0x02000001) + +#define IS_I2C_CLEAR_IT(IT) ((((IT) & (uint16_t)0x20FF) == 0x00) && ((IT) != (uint16_t)0x00)) + +#define IS_I2C_GET_IT(IT) (((IT) == I2C_IT_SMBALERT) || ((IT) == I2C_IT_TIMEOUT) || \ + ((IT) == I2C_IT_PECERR) || ((IT) == I2C_IT_OVR) || \ + ((IT) == I2C_IT_AF) || ((IT) == I2C_IT_ARLO) || \ + ((IT) == I2C_IT_BERR) || ((IT) == I2C_IT_TXE) || \ + ((IT) == I2C_IT_RXNE) || ((IT) == I2C_IT_STOPF) || \ + ((IT) == I2C_IT_ADD10) || ((IT) == I2C_IT_BTF) || \ + ((IT) == I2C_IT_ADDR) || ((IT) == I2C_IT_SB)) +/** + * @} + */ + +/** @defgroup I2C_flags_definition + * @{ + */ + +/** + * @brief SR2 register flags + */ + +#define I2C_FLAG_DUALF ((uint32_t)0x00800000) +#define I2C_FLAG_SMBHOST ((uint32_t)0x00400000) +#define I2C_FLAG_SMBDEFAULT ((uint32_t)0x00200000) +#define I2C_FLAG_GENCALL ((uint32_t)0x00100000) +#define I2C_FLAG_TRA ((uint32_t)0x00040000) +#define I2C_FLAG_BUSY ((uint32_t)0x00020000) +#define I2C_FLAG_MSL ((uint32_t)0x00010000) + +/** + * @brief SR1 register flags + */ + +#define I2C_FLAG_SMBALERT ((uint32_t)0x10008000) +#define I2C_FLAG_TIMEOUT ((uint32_t)0x10004000) +#define I2C_FLAG_PECERR ((uint32_t)0x10001000) +#define I2C_FLAG_OVR ((uint32_t)0x10000800) +#define I2C_FLAG_AF ((uint32_t)0x10000400) +#define I2C_FLAG_ARLO ((uint32_t)0x10000200) +#define I2C_FLAG_BERR ((uint32_t)0x10000100) +#define I2C_FLAG_TXE ((uint32_t)0x10000080) +#define I2C_FLAG_RXNE ((uint32_t)0x10000040) +#define I2C_FLAG_STOPF ((uint32_t)0x10000010) +#define I2C_FLAG_ADD10 ((uint32_t)0x10000008) +#define I2C_FLAG_BTF ((uint32_t)0x10000004) +#define I2C_FLAG_ADDR ((uint32_t)0x10000002) +#define I2C_FLAG_SB ((uint32_t)0x10000001) + +#define IS_I2C_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0x20FF) == 0x00) && ((FLAG) != (uint16_t)0x00)) + +#define IS_I2C_GET_FLAG(FLAG) (((FLAG) == I2C_FLAG_DUALF) || ((FLAG) == I2C_FLAG_SMBHOST) || \ + ((FLAG) == I2C_FLAG_SMBDEFAULT) || ((FLAG) == I2C_FLAG_GENCALL) || \ + ((FLAG) == I2C_FLAG_TRA) || ((FLAG) == I2C_FLAG_BUSY) || \ + ((FLAG) == I2C_FLAG_MSL) || ((FLAG) == I2C_FLAG_SMBALERT) || \ + ((FLAG) == I2C_FLAG_TIMEOUT) || ((FLAG) == I2C_FLAG_PECERR) || \ + ((FLAG) == I2C_FLAG_OVR) || ((FLAG) == I2C_FLAG_AF) || \ + ((FLAG) == I2C_FLAG_ARLO) || ((FLAG) == I2C_FLAG_BERR) || \ + ((FLAG) == I2C_FLAG_TXE) || ((FLAG) == I2C_FLAG_RXNE) || \ + ((FLAG) == I2C_FLAG_STOPF) || ((FLAG) == I2C_FLAG_ADD10) || \ + ((FLAG) == I2C_FLAG_BTF) || ((FLAG) == I2C_FLAG_ADDR) || \ + ((FLAG) == I2C_FLAG_SB)) +/** + * @} + */ + +/** @defgroup I2C_Events + * @{ + */ + +/*======================================== + + I2C Master Events (Events grouped in order of communication) + ==========================================*/ +/** + * @brief Communication start + * + * After sending the START condition (I2C_GenerateSTART() function) the master + * has to wait for this event. It means that the Start condition has been correctly + * released on the I2C bus (the bus is free, no other devices is communicating). + * + */ +/* --EV5 */ +#define I2C_EVENT_MASTER_MODE_SELECT ((uint32_t)0x00030001) /* BUSY, MSL and SB flag */ + +/** + * @brief Address Acknowledge + * + * After checking on EV5 (start condition correctly released on the bus), the + * master sends the address of the slave(s) with which it will communicate + * (I2C_Send7bitAddress() function, it also determines the direction of the communication: + * Master transmitter or Receiver). Then the master has to wait that a slave acknowledges + * his address. If an acknowledge is sent on the bus, one of the following events will + * be set: + * + * 1) In case of Master Receiver (7-bit addressing): the I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED + * event is set. + * + * 2) In case of Master Transmitter (7-bit addressing): the I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED + * is set + * + * 3) In case of 10-Bit addressing mode, the master (just after generating the START + * and checking on EV5) has to send the header of 10-bit addressing mode (I2C_SendData() + * function). Then master should wait on EV9. It means that the 10-bit addressing + * header has been correctly sent on the bus. Then master should send the second part of + * the 10-bit address (LSB) using the function I2C_Send7bitAddress(). Then master + * should wait for event EV6. + * + */ + +/* --EV6 */ +#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED ((uint32_t)0x00070082) /* BUSY, MSL, ADDR, TXE and TRA flags */ +#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED ((uint32_t)0x00030002) /* BUSY, MSL and ADDR flags */ +/* --EV9 */ +#define I2C_EVENT_MASTER_MODE_ADDRESS10 ((uint32_t)0x00030008) /* BUSY, MSL and ADD10 flags */ + +/** + * @brief Communication events + * + * If a communication is established (START condition generated and slave address + * acknowledged) then the master has to check on one of the following events for + * communication procedures: + * + * 1) Master Receiver mode: The master has to wait on the event EV7 then to read + * the data received from the slave (I2C_ReceiveData() function). + * + * 2) Master Transmitter mode: The master has to send data (I2C_SendData() + * function) then to wait on event EV8 or EV8_2. + * These two events are similar: + * - EV8 means that the data has been written in the data register and is + * being shifted out. + * - EV8_2 means that the data has been physically shifted out and output + * on the bus. + * In most cases, using EV8 is sufficient for the application. + * Using EV8_2 leads to a slower communication but ensure more reliable test. + * EV8_2 is also more suitable than EV8 for testing on the last data transmission + * (before Stop condition generation). + * + * @note In case the user software does not guarantee that this event EV7 is + * managed before the current byte end of transfer, then user may check on EV7 + * and BTF flag at the same time (ie. (I2C_EVENT_MASTER_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Master RECEIVER mode -----------------------------*/ +/* --EV7 */ +#define I2C_EVENT_MASTER_BYTE_RECEIVED ((uint32_t)0x00030040) /* BUSY, MSL and RXNE flags */ + +/* Master TRANSMITTER mode --------------------------*/ +/* --EV8 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTING ((uint32_t)0x00070080) /* TRA, BUSY, MSL, TXE flags */ +/* --EV8_2 */ +#define I2C_EVENT_MASTER_BYTE_TRANSMITTED ((uint32_t)0x00070084) /* TRA, BUSY, MSL, TXE and BTF flags */ + + +/*======================================== + + I2C Slave Events (Events grouped in order of communication) + ==========================================*/ + +/** + * @brief Communication start events + * + * Wait on one of these events at the start of the communication. It means that + * the I2C peripheral detected a Start condition on the bus (generated by master + * device) followed by the peripheral address. The peripheral generates an ACK + * condition on the bus (if the acknowledge feature is enabled through function + * I2C_AcknowledgeConfig()) and the events listed above are set : + * + * 1) In normal case (only one address managed by the slave), when the address + * sent by the master matches the own address of the peripheral (configured by + * I2C_OwnAddress1 field) the I2C_EVENT_SLAVE_XXX_ADDRESS_MATCHED event is set + * (where XXX could be TRANSMITTER or RECEIVER). + * + * 2) In case the address sent by the master matches the second address of the + * peripheral (configured by the function I2C_OwnAddress2Config() and enabled + * by the function I2C_DualAddressCmd()) the events I2C_EVENT_SLAVE_XXX_SECONDADDRESS_MATCHED + * (where XXX could be TRANSMITTER or RECEIVER) are set. + * + * 3) In case the address sent by the master is General Call (address 0x00) and + * if the General Call is enabled for the peripheral (using function I2C_GeneralCallCmd()) + * the following event is set I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED. + * + */ + +/* --EV1 (all the events below are variants of EV1) */ +/* 1) Case of One Single Address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED ((uint32_t)0x00020002) /* BUSY and ADDR flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED ((uint32_t)0x00060082) /* TRA, BUSY, TXE and ADDR flags */ + +/* 2) Case of Dual address managed by the slave */ +#define I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED ((uint32_t)0x00820000) /* DUALF and BUSY flags */ +#define I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED ((uint32_t)0x00860080) /* DUALF, TRA, BUSY and TXE flags */ + +/* 3) Case of General Call enabled for the slave */ +#define I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED ((uint32_t)0x00120000) /* GENCALL and BUSY flags */ + +/** + * @brief Communication events + * + * Wait on one of these events when EV1 has already been checked and: + * + * - Slave RECEIVER mode: + * - EV2: When the application is expecting a data byte to be received. + * - EV4: When the application is expecting the end of the communication: master + * sends a stop condition and data transmission is stopped. + * + * - Slave Transmitter mode: + * - EV3: When a byte has been transmitted by the slave and the application is expecting + * the end of the byte transmission. The two events I2C_EVENT_SLAVE_BYTE_TRANSMITTED and + * I2C_EVENT_SLAVE_BYTE_TRANSMITTING are similar. The second one can optionally be + * used when the user software doesn't guarantee the EV3 is managed before the + * current byte end of transfer. + * - EV3_2: When the master sends a NACK in order to tell slave that data transmission + * shall end (before sending the STOP condition). In this case slave has to stop sending + * data bytes and expect a Stop condition on the bus. + * + * @note In case the user software does not guarantee that the event EV2 is + * managed before the current byte end of transfer, then user may check on EV2 + * and BTF flag at the same time (ie. (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_BTF)). + * In this case the communication may be slower. + * + */ + +/* Slave RECEIVER mode --------------------------*/ +/* --EV2 */ +#define I2C_EVENT_SLAVE_BYTE_RECEIVED ((uint32_t)0x00020040) /* BUSY and RXNE flags */ +/* --EV4 */ +#define I2C_EVENT_SLAVE_STOP_DETECTED ((uint32_t)0x00000010) /* STOPF flag */ + +/* Slave TRANSMITTER mode -----------------------*/ +/* --EV3 */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTED ((uint32_t)0x00060084) /* TRA, BUSY, TXE and BTF flags */ +#define I2C_EVENT_SLAVE_BYTE_TRANSMITTING ((uint32_t)0x00060080) /* TRA, BUSY and TXE flags */ +/* --EV3_2 */ +#define I2C_EVENT_SLAVE_ACK_FAILURE ((uint32_t)0x00000400) /* AF flag */ + +/*=========================== End of Events Description ==========================================*/ + +#define IS_I2C_EVENT(EVENT) (((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_RECEIVED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_BYTE_TRANSMITTED) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF)) || \ + ((EVENT) == (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL)) || \ + ((EVENT) == I2C_EVENT_SLAVE_STOP_DETECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_SELECT) || \ + ((EVENT) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_RECEIVED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTED) || \ + ((EVENT) == I2C_EVENT_MASTER_BYTE_TRANSMITTING) || \ + ((EVENT) == I2C_EVENT_MASTER_MODE_ADDRESS10) || \ + ((EVENT) == I2C_EVENT_SLAVE_ACK_FAILURE)) +/** + * @} + */ + +/** @defgroup I2C_own_address1 + * @{ + */ + +#define IS_I2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x3FF) +/** + * @} + */ + +/** @defgroup I2C_clock_speed + * @{ + */ + +#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) >= 0x1) && ((SPEED) <= 400000)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Exported_Functions + * @{ + */ + +void I2C_DeInit(I2C_TypeDef* I2Cx); +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct); +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct); +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address); +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState); +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data); +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx); +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction); +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register); +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition); +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert); +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition); +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState); +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx); +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState); +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle); + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applications as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occurred. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the limitations of I2C_GetFlagStatus() function (see below). + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defined by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT); +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx); +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +/** + * + ******************************************************************************* + */ + +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG); +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT); +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_I2C_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h new file mode 100755 index 0000000000..7f5ab7642c --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_iwdg.h @@ -0,0 +1,140 @@ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the IWDG + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_IWDG_H +#define __STM32F10x_IWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup IWDG + * @{ + */ + +/** @defgroup IWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Constants + * @{ + */ + +/** @defgroup IWDG_WriteAccess + * @{ + */ + +#define IWDG_WriteAccess_Enable ((uint16_t)0x5555) +#define IWDG_WriteAccess_Disable ((uint16_t)0x0000) +#define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \ + ((ACCESS) == IWDG_WriteAccess_Disable)) +/** + * @} + */ + +/** @defgroup IWDG_prescaler + * @{ + */ + +#define IWDG_Prescaler_4 ((uint8_t)0x00) +#define IWDG_Prescaler_8 ((uint8_t)0x01) +#define IWDG_Prescaler_16 ((uint8_t)0x02) +#define IWDG_Prescaler_32 ((uint8_t)0x03) +#define IWDG_Prescaler_64 ((uint8_t)0x04) +#define IWDG_Prescaler_128 ((uint8_t)0x05) +#define IWDG_Prescaler_256 ((uint8_t)0x06) +#define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \ + ((PRESCALER) == IWDG_Prescaler_8) || \ + ((PRESCALER) == IWDG_Prescaler_16) || \ + ((PRESCALER) == IWDG_Prescaler_32) || \ + ((PRESCALER) == IWDG_Prescaler_64) || \ + ((PRESCALER) == IWDG_Prescaler_128)|| \ + ((PRESCALER) == IWDG_Prescaler_256)) +/** + * @} + */ + +/** @defgroup IWDG_Flag + * @{ + */ + +#define IWDG_FLAG_PVU ((uint16_t)0x0001) +#define IWDG_FLAG_RVU ((uint16_t)0x0002) +#define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU)) +#define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Exported_Functions + * @{ + */ + +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess); +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler); +void IWDG_SetReload(uint16_t Reload); +void IWDG_ReloadCounter(void); +void IWDG_Enable(void); +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_IWDG_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h new file mode 100755 index 0000000000..76e6ce91f9 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_pwr.h @@ -0,0 +1,156 @@ +/** + ****************************************************************************** + * @file stm32f10x_pwr.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the PWR firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_PWR_H +#define __STM32F10x_PWR_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup PWR + * @{ + */ + +/** @defgroup PWR_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Constants + * @{ + */ + +/** @defgroup PVD_detection_level + * @{ + */ + +#define PWR_PVDLevel_2V2 ((uint32_t)0x00000000) +#define PWR_PVDLevel_2V3 ((uint32_t)0x00000020) +#define PWR_PVDLevel_2V4 ((uint32_t)0x00000040) +#define PWR_PVDLevel_2V5 ((uint32_t)0x00000060) +#define PWR_PVDLevel_2V6 ((uint32_t)0x00000080) +#define PWR_PVDLevel_2V7 ((uint32_t)0x000000A0) +#define PWR_PVDLevel_2V8 ((uint32_t)0x000000C0) +#define PWR_PVDLevel_2V9 ((uint32_t)0x000000E0) +#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLevel_2V2) || ((LEVEL) == PWR_PVDLevel_2V3)|| \ + ((LEVEL) == PWR_PVDLevel_2V4) || ((LEVEL) == PWR_PVDLevel_2V5)|| \ + ((LEVEL) == PWR_PVDLevel_2V6) || ((LEVEL) == PWR_PVDLevel_2V7)|| \ + ((LEVEL) == PWR_PVDLevel_2V8) || ((LEVEL) == PWR_PVDLevel_2V9)) +/** + * @} + */ + +/** @defgroup Regulator_state_is_STOP_mode + * @{ + */ + +#define PWR_Regulator_ON ((uint32_t)0x00000000) +#define PWR_Regulator_LowPower ((uint32_t)0x00000001) +#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_Regulator_ON) || \ + ((REGULATOR) == PWR_Regulator_LowPower)) +/** + * @} + */ + +/** @defgroup STOP_mode_entry + * @{ + */ + +#define PWR_STOPEntry_WFI ((uint8_t)0x01) +#define PWR_STOPEntry_WFE ((uint8_t)0x02) +#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPEntry_WFI) || ((ENTRY) == PWR_STOPEntry_WFE)) + +/** + * @} + */ + +/** @defgroup PWR_Flag + * @{ + */ + +#define PWR_FLAG_WU ((uint32_t)0x00000001) +#define PWR_FLAG_SB ((uint32_t)0x00000002) +#define PWR_FLAG_PVDO ((uint32_t)0x00000004) +#define IS_PWR_GET_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB) || \ + ((FLAG) == PWR_FLAG_PVDO)) + +#define IS_PWR_CLEAR_FLAG(FLAG) (((FLAG) == PWR_FLAG_WU) || ((FLAG) == PWR_FLAG_SB)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Exported_Functions + * @{ + */ + +void PWR_DeInit(void); +void PWR_BackupAccessCmd(FunctionalState NewState); +void PWR_PVDCmd(FunctionalState NewState); +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel); +void PWR_WakeUpPinCmd(FunctionalState NewState); +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry); +void PWR_EnterSTANDBYMode(void); +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG); +void PWR_ClearFlag(uint32_t PWR_FLAG); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_PWR_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h new file mode 100755 index 0000000000..b3b7d821d7 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rcc.h @@ -0,0 +1,727 @@ +/** + ****************************************************************************** + * @file stm32f10x_rcc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the RCC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RCC_H +#define __STM32F10x_RCC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RCC + * @{ + */ + +/** @defgroup RCC_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SYSCLK_Frequency; /*!< returns SYSCLK clock frequency expressed in Hz */ + uint32_t HCLK_Frequency; /*!< returns HCLK clock frequency expressed in Hz */ + uint32_t PCLK1_Frequency; /*!< returns PCLK1 clock frequency expressed in Hz */ + uint32_t PCLK2_Frequency; /*!< returns PCLK2 clock frequency expressed in Hz */ + uint32_t ADCCLK_Frequency; /*!< returns ADCCLK clock frequency expressed in Hz */ +}RCC_ClocksTypeDef; + +/** + * @} + */ + +/** @defgroup RCC_Exported_Constants + * @{ + */ + +/** @defgroup HSE_configuration + * @{ + */ + +#define RCC_HSE_OFF ((uint32_t)0x00000000) +#define RCC_HSE_ON ((uint32_t)0x00010000) +#define RCC_HSE_Bypass ((uint32_t)0x00040000) +#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ + ((HSE) == RCC_HSE_Bypass)) + +/** + * @} + */ + +/** @defgroup PLL_entry_clock_source + * @{ + */ + +#define RCC_PLLSource_HSI_Div2 ((uint32_t)0x00000000) + +#if !defined (STM32F10X_LD_VL) && !defined (STM32F10X_MD_VL) && !defined (STM32F10X_HD_VL) && !defined (STM32F10X_CL) + #define RCC_PLLSource_HSE_Div1 ((uint32_t)0x00010000) + #define RCC_PLLSource_HSE_Div2 ((uint32_t)0x00030000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div1) || \ + ((SOURCE) == RCC_PLLSource_HSE_Div2)) +#else + #define RCC_PLLSource_PREDIV1 ((uint32_t)0x00010000) + #define IS_RCC_PLL_SOURCE(SOURCE) (((SOURCE) == RCC_PLLSource_HSI_Div2) || \ + ((SOURCE) == RCC_PLLSource_PREDIV1)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup PLL_multiplication_factor + * @{ + */ +#ifndef STM32F10X_CL + #define RCC_PLLMul_2 ((uint32_t)0x00000000) + #define RCC_PLLMul_3 ((uint32_t)0x00040000) + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_10 ((uint32_t)0x00200000) + #define RCC_PLLMul_11 ((uint32_t)0x00240000) + #define RCC_PLLMul_12 ((uint32_t)0x00280000) + #define RCC_PLLMul_13 ((uint32_t)0x002C0000) + #define RCC_PLLMul_14 ((uint32_t)0x00300000) + #define RCC_PLLMul_15 ((uint32_t)0x00340000) + #define RCC_PLLMul_16 ((uint32_t)0x00380000) + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_2) || ((MUL) == RCC_PLLMul_3) || \ + ((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_10) || ((MUL) == RCC_PLLMul_11) || \ + ((MUL) == RCC_PLLMul_12) || ((MUL) == RCC_PLLMul_13) || \ + ((MUL) == RCC_PLLMul_14) || ((MUL) == RCC_PLLMul_15) || \ + ((MUL) == RCC_PLLMul_16)) + +#else + #define RCC_PLLMul_4 ((uint32_t)0x00080000) + #define RCC_PLLMul_5 ((uint32_t)0x000C0000) + #define RCC_PLLMul_6 ((uint32_t)0x00100000) + #define RCC_PLLMul_7 ((uint32_t)0x00140000) + #define RCC_PLLMul_8 ((uint32_t)0x00180000) + #define RCC_PLLMul_9 ((uint32_t)0x001C0000) + #define RCC_PLLMul_6_5 ((uint32_t)0x00340000) + + #define IS_RCC_PLL_MUL(MUL) (((MUL) == RCC_PLLMul_4) || ((MUL) == RCC_PLLMul_5) || \ + ((MUL) == RCC_PLLMul_6) || ((MUL) == RCC_PLLMul_7) || \ + ((MUL) == RCC_PLLMul_8) || ((MUL) == RCC_PLLMul_9) || \ + ((MUL) == RCC_PLLMul_6_5)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup PREDIV1_division_factor + * @{ + */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define RCC_PREDIV1_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV1_Div2 ((uint32_t)0x00000001) + #define RCC_PREDIV1_Div3 ((uint32_t)0x00000002) + #define RCC_PREDIV1_Div4 ((uint32_t)0x00000003) + #define RCC_PREDIV1_Div5 ((uint32_t)0x00000004) + #define RCC_PREDIV1_Div6 ((uint32_t)0x00000005) + #define RCC_PREDIV1_Div7 ((uint32_t)0x00000006) + #define RCC_PREDIV1_Div8 ((uint32_t)0x00000007) + #define RCC_PREDIV1_Div9 ((uint32_t)0x00000008) + #define RCC_PREDIV1_Div10 ((uint32_t)0x00000009) + #define RCC_PREDIV1_Div11 ((uint32_t)0x0000000A) + #define RCC_PREDIV1_Div12 ((uint32_t)0x0000000B) + #define RCC_PREDIV1_Div13 ((uint32_t)0x0000000C) + #define RCC_PREDIV1_Div14 ((uint32_t)0x0000000D) + #define RCC_PREDIV1_Div15 ((uint32_t)0x0000000E) + #define RCC_PREDIV1_Div16 ((uint32_t)0x0000000F) + + #define IS_RCC_PREDIV1(PREDIV1) (((PREDIV1) == RCC_PREDIV1_Div1) || ((PREDIV1) == RCC_PREDIV1_Div2) || \ + ((PREDIV1) == RCC_PREDIV1_Div3) || ((PREDIV1) == RCC_PREDIV1_Div4) || \ + ((PREDIV1) == RCC_PREDIV1_Div5) || ((PREDIV1) == RCC_PREDIV1_Div6) || \ + ((PREDIV1) == RCC_PREDIV1_Div7) || ((PREDIV1) == RCC_PREDIV1_Div8) || \ + ((PREDIV1) == RCC_PREDIV1_Div9) || ((PREDIV1) == RCC_PREDIV1_Div10) || \ + ((PREDIV1) == RCC_PREDIV1_Div11) || ((PREDIV1) == RCC_PREDIV1_Div12) || \ + ((PREDIV1) == RCC_PREDIV1_Div13) || ((PREDIV1) == RCC_PREDIV1_Div14) || \ + ((PREDIV1) == RCC_PREDIV1_Div15) || ((PREDIV1) == RCC_PREDIV1_Div16)) +#endif +/** + * @} + */ + + +/** @defgroup PREDIV1_clock_source + * @{ + */ +#ifdef STM32F10X_CL +/* PREDIV1 clock source (for STM32 connectivity line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + #define RCC_PREDIV1_Source_PLL2 ((uint32_t)0x00010000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE) || \ + ((SOURCE) == RCC_PREDIV1_Source_PLL2)) +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/* PREDIV1 clock source (for STM32 Value line devices) */ + #define RCC_PREDIV1_Source_HSE ((uint32_t)0x00000000) + + #define IS_RCC_PREDIV1_SOURCE(SOURCE) (((SOURCE) == RCC_PREDIV1_Source_HSE)) +#endif +/** + * @} + */ + +#ifdef STM32F10X_CL +/** @defgroup PREDIV2_division_factor + * @{ + */ + + #define RCC_PREDIV2_Div1 ((uint32_t)0x00000000) + #define RCC_PREDIV2_Div2 ((uint32_t)0x00000010) + #define RCC_PREDIV2_Div3 ((uint32_t)0x00000020) + #define RCC_PREDIV2_Div4 ((uint32_t)0x00000030) + #define RCC_PREDIV2_Div5 ((uint32_t)0x00000040) + #define RCC_PREDIV2_Div6 ((uint32_t)0x00000050) + #define RCC_PREDIV2_Div7 ((uint32_t)0x00000060) + #define RCC_PREDIV2_Div8 ((uint32_t)0x00000070) + #define RCC_PREDIV2_Div9 ((uint32_t)0x00000080) + #define RCC_PREDIV2_Div10 ((uint32_t)0x00000090) + #define RCC_PREDIV2_Div11 ((uint32_t)0x000000A0) + #define RCC_PREDIV2_Div12 ((uint32_t)0x000000B0) + #define RCC_PREDIV2_Div13 ((uint32_t)0x000000C0) + #define RCC_PREDIV2_Div14 ((uint32_t)0x000000D0) + #define RCC_PREDIV2_Div15 ((uint32_t)0x000000E0) + #define RCC_PREDIV2_Div16 ((uint32_t)0x000000F0) + + #define IS_RCC_PREDIV2(PREDIV2) (((PREDIV2) == RCC_PREDIV2_Div1) || ((PREDIV2) == RCC_PREDIV2_Div2) || \ + ((PREDIV2) == RCC_PREDIV2_Div3) || ((PREDIV2) == RCC_PREDIV2_Div4) || \ + ((PREDIV2) == RCC_PREDIV2_Div5) || ((PREDIV2) == RCC_PREDIV2_Div6) || \ + ((PREDIV2) == RCC_PREDIV2_Div7) || ((PREDIV2) == RCC_PREDIV2_Div8) || \ + ((PREDIV2) == RCC_PREDIV2_Div9) || ((PREDIV2) == RCC_PREDIV2_Div10) || \ + ((PREDIV2) == RCC_PREDIV2_Div11) || ((PREDIV2) == RCC_PREDIV2_Div12) || \ + ((PREDIV2) == RCC_PREDIV2_Div13) || ((PREDIV2) == RCC_PREDIV2_Div14) || \ + ((PREDIV2) == RCC_PREDIV2_Div15) || ((PREDIV2) == RCC_PREDIV2_Div16)) +/** + * @} + */ + + +/** @defgroup PLL2_multiplication_factor + * @{ + */ + + #define RCC_PLL2Mul_8 ((uint32_t)0x00000600) + #define RCC_PLL2Mul_9 ((uint32_t)0x00000700) + #define RCC_PLL2Mul_10 ((uint32_t)0x00000800) + #define RCC_PLL2Mul_11 ((uint32_t)0x00000900) + #define RCC_PLL2Mul_12 ((uint32_t)0x00000A00) + #define RCC_PLL2Mul_13 ((uint32_t)0x00000B00) + #define RCC_PLL2Mul_14 ((uint32_t)0x00000C00) + #define RCC_PLL2Mul_16 ((uint32_t)0x00000E00) + #define RCC_PLL2Mul_20 ((uint32_t)0x00000F00) + + #define IS_RCC_PLL2_MUL(MUL) (((MUL) == RCC_PLL2Mul_8) || ((MUL) == RCC_PLL2Mul_9) || \ + ((MUL) == RCC_PLL2Mul_10) || ((MUL) == RCC_PLL2Mul_11) || \ + ((MUL) == RCC_PLL2Mul_12) || ((MUL) == RCC_PLL2Mul_13) || \ + ((MUL) == RCC_PLL2Mul_14) || ((MUL) == RCC_PLL2Mul_16) || \ + ((MUL) == RCC_PLL2Mul_20)) +/** + * @} + */ + + +/** @defgroup PLL3_multiplication_factor + * @{ + */ + + #define RCC_PLL3Mul_8 ((uint32_t)0x00006000) + #define RCC_PLL3Mul_9 ((uint32_t)0x00007000) + #define RCC_PLL3Mul_10 ((uint32_t)0x00008000) + #define RCC_PLL3Mul_11 ((uint32_t)0x00009000) + #define RCC_PLL3Mul_12 ((uint32_t)0x0000A000) + #define RCC_PLL3Mul_13 ((uint32_t)0x0000B000) + #define RCC_PLL3Mul_14 ((uint32_t)0x0000C000) + #define RCC_PLL3Mul_16 ((uint32_t)0x0000E000) + #define RCC_PLL3Mul_20 ((uint32_t)0x0000F000) + + #define IS_RCC_PLL3_MUL(MUL) (((MUL) == RCC_PLL3Mul_8) || ((MUL) == RCC_PLL3Mul_9) || \ + ((MUL) == RCC_PLL3Mul_10) || ((MUL) == RCC_PLL3Mul_11) || \ + ((MUL) == RCC_PLL3Mul_12) || ((MUL) == RCC_PLL3Mul_13) || \ + ((MUL) == RCC_PLL3Mul_14) || ((MUL) == RCC_PLL3Mul_16) || \ + ((MUL) == RCC_PLL3Mul_20)) +/** + * @} + */ + +#endif /* STM32F10X_CL */ + + +/** @defgroup System_clock_source + * @{ + */ + +#define RCC_SYSCLKSource_HSI ((uint32_t)0x00000000) +#define RCC_SYSCLKSource_HSE ((uint32_t)0x00000001) +#define RCC_SYSCLKSource_PLLCLK ((uint32_t)0x00000002) +#define IS_RCC_SYSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSource_HSI) || \ + ((SOURCE) == RCC_SYSCLKSource_HSE) || \ + ((SOURCE) == RCC_SYSCLKSource_PLLCLK)) +/** + * @} + */ + +/** @defgroup AHB_clock_source + * @{ + */ + +#define RCC_SYSCLK_Div1 ((uint32_t)0x00000000) +#define RCC_SYSCLK_Div2 ((uint32_t)0x00000080) +#define RCC_SYSCLK_Div4 ((uint32_t)0x00000090) +#define RCC_SYSCLK_Div8 ((uint32_t)0x000000A0) +#define RCC_SYSCLK_Div16 ((uint32_t)0x000000B0) +#define RCC_SYSCLK_Div64 ((uint32_t)0x000000C0) +#define RCC_SYSCLK_Div128 ((uint32_t)0x000000D0) +#define RCC_SYSCLK_Div256 ((uint32_t)0x000000E0) +#define RCC_SYSCLK_Div512 ((uint32_t)0x000000F0) +#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_Div1) || ((HCLK) == RCC_SYSCLK_Div2) || \ + ((HCLK) == RCC_SYSCLK_Div4) || ((HCLK) == RCC_SYSCLK_Div8) || \ + ((HCLK) == RCC_SYSCLK_Div16) || ((HCLK) == RCC_SYSCLK_Div64) || \ + ((HCLK) == RCC_SYSCLK_Div128) || ((HCLK) == RCC_SYSCLK_Div256) || \ + ((HCLK) == RCC_SYSCLK_Div512)) +/** + * @} + */ + +/** @defgroup APB1_APB2_clock_source + * @{ + */ + +#define RCC_HCLK_Div1 ((uint32_t)0x00000000) +#define RCC_HCLK_Div2 ((uint32_t)0x00000400) +#define RCC_HCLK_Div4 ((uint32_t)0x00000500) +#define RCC_HCLK_Div8 ((uint32_t)0x00000600) +#define RCC_HCLK_Div16 ((uint32_t)0x00000700) +#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_Div1) || ((PCLK) == RCC_HCLK_Div2) || \ + ((PCLK) == RCC_HCLK_Div4) || ((PCLK) == RCC_HCLK_Div8) || \ + ((PCLK) == RCC_HCLK_Div16)) +/** + * @} + */ + +/** @defgroup RCC_Interrupt_source + * @{ + */ + +#define RCC_IT_LSIRDY ((uint8_t)0x01) +#define RCC_IT_LSERDY ((uint8_t)0x02) +#define RCC_IT_HSIRDY ((uint8_t)0x04) +#define RCC_IT_HSERDY ((uint8_t)0x08) +#define RCC_IT_PLLRDY ((uint8_t)0x10) +#define RCC_IT_CSS ((uint8_t)0x80) + +#ifndef STM32F10X_CL + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0xE0) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS)) + #define IS_RCC_CLEAR_IT(IT) ((((IT) & (uint8_t)0x60) == 0x00) && ((IT) != 0x00)) +#else + #define RCC_IT_PLL2RDY ((uint8_t)0x20) + #define RCC_IT_PLL3RDY ((uint8_t)0x40) + #define IS_RCC_IT(IT) ((((IT) & (uint8_t)0x80) == 0x00) && ((IT) != 0x00)) + #define IS_RCC_GET_IT(IT) (((IT) == RCC_IT_LSIRDY) || ((IT) == RCC_IT_LSERDY) || \ + ((IT) == RCC_IT_HSIRDY) || ((IT) == RCC_IT_HSERDY) || \ + ((IT) == RCC_IT_PLLRDY) || ((IT) == RCC_IT_CSS) || \ + ((IT) == RCC_IT_PLL2RDY) || ((IT) == RCC_IT_PLL3RDY)) + #define IS_RCC_CLEAR_IT(IT) ((IT) != 0x00) +#endif /* STM32F10X_CL */ + + +/** + * @} + */ + +#ifndef STM32F10X_CL +/** @defgroup USB_Device_clock_source + * @{ + */ + + #define RCC_USBCLKSource_PLLCLK_1Div5 ((uint8_t)0x00) + #define RCC_USBCLKSource_PLLCLK_Div1 ((uint8_t)0x01) + + #define IS_RCC_USBCLK_SOURCE(SOURCE) (((SOURCE) == RCC_USBCLKSource_PLLCLK_1Div5) || \ + ((SOURCE) == RCC_USBCLKSource_PLLCLK_Div1)) +/** + * @} + */ +#else +/** @defgroup USB_OTG_FS_clock_source + * @{ + */ + #define RCC_OTGFSCLKSource_PLLVCO_Div3 ((uint8_t)0x00) + #define RCC_OTGFSCLKSource_PLLVCO_Div2 ((uint8_t)0x01) + + #define IS_RCC_OTGFSCLK_SOURCE(SOURCE) (((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div3) || \ + ((SOURCE) == RCC_OTGFSCLKSource_PLLVCO_Div2)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +#ifdef STM32F10X_CL +/** @defgroup I2S2_clock_source + * @{ + */ + #define RCC_I2S2CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S2CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S2CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S2CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S2CLKSource_PLL3_VCO)) +/** + * @} + */ + +/** @defgroup I2S3_clock_source + * @{ + */ + #define RCC_I2S3CLKSource_SYSCLK ((uint8_t)0x00) + #define RCC_I2S3CLKSource_PLL3_VCO ((uint8_t)0x01) + + #define IS_RCC_I2S3CLK_SOURCE(SOURCE) (((SOURCE) == RCC_I2S3CLKSource_SYSCLK) || \ + ((SOURCE) == RCC_I2S3CLKSource_PLL3_VCO)) +/** + * @} + */ +#endif /* STM32F10X_CL */ + + +/** @defgroup ADC_clock_source + * @{ + */ + +#define RCC_PCLK2_Div2 ((uint32_t)0x00000000) +#define RCC_PCLK2_Div4 ((uint32_t)0x00004000) +#define RCC_PCLK2_Div6 ((uint32_t)0x00008000) +#define RCC_PCLK2_Div8 ((uint32_t)0x0000C000) +#define IS_RCC_ADCCLK(ADCCLK) (((ADCCLK) == RCC_PCLK2_Div2) || ((ADCCLK) == RCC_PCLK2_Div4) || \ + ((ADCCLK) == RCC_PCLK2_Div6) || ((ADCCLK) == RCC_PCLK2_Div8)) +/** + * @} + */ + +/** @defgroup LSE_configuration + * @{ + */ + +#define RCC_LSE_OFF ((uint8_t)0x00) +#define RCC_LSE_ON ((uint8_t)0x01) +#define RCC_LSE_Bypass ((uint8_t)0x04) +#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ + ((LSE) == RCC_LSE_Bypass)) +/** + * @} + */ + +/** @defgroup RTC_clock_source + * @{ + */ + +#define RCC_RTCCLKSource_LSE ((uint32_t)0x00000100) +#define RCC_RTCCLKSource_LSI ((uint32_t)0x00000200) +#define RCC_RTCCLKSource_HSE_Div128 ((uint32_t)0x00000300) +#define IS_RCC_RTCCLK_SOURCE(SOURCE) (((SOURCE) == RCC_RTCCLKSource_LSE) || \ + ((SOURCE) == RCC_RTCCLKSource_LSI) || \ + ((SOURCE) == RCC_RTCCLKSource_HSE_Div128)) +/** + * @} + */ + +/** @defgroup AHB_peripheral + * @{ + */ + +#define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001) +#define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002) +#define RCC_AHBPeriph_SRAM ((uint32_t)0x00000004) +#define RCC_AHBPeriph_FLITF ((uint32_t)0x00000010) +#define RCC_AHBPeriph_CRC ((uint32_t)0x00000040) + +#ifndef STM32F10X_CL + #define RCC_AHBPeriph_FSMC ((uint32_t)0x00000100) + #define RCC_AHBPeriph_SDIO ((uint32_t)0x00000400) + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFFFAA8) == 0x00) && ((PERIPH) != 0x00)) +#else + #define RCC_AHBPeriph_OTG_FS ((uint32_t)0x00001000) + #define RCC_AHBPeriph_ETH_MAC ((uint32_t)0x00004000) + #define RCC_AHBPeriph_ETH_MAC_Tx ((uint32_t)0x00008000) + #define RCC_AHBPeriph_ETH_MAC_Rx ((uint32_t)0x00010000) + + #define IS_RCC_AHB_PERIPH(PERIPH) ((((PERIPH) & 0xFFFE2FA8) == 0x00) && ((PERIPH) != 0x00)) + #define IS_RCC_AHB_PERIPH_RESET(PERIPH) ((((PERIPH) & 0xFFFFAFFF) == 0x00) && ((PERIPH) != 0x00)) +#endif /* STM32F10X_CL */ +/** + * @} + */ + +/** @defgroup APB2_peripheral + * @{ + */ + +#define RCC_APB2Periph_AFIO ((uint32_t)0x00000001) +#define RCC_APB2Periph_GPIOA ((uint32_t)0x00000004) +#define RCC_APB2Periph_GPIOB ((uint32_t)0x00000008) +#define RCC_APB2Periph_GPIOC ((uint32_t)0x00000010) +#define RCC_APB2Periph_GPIOD ((uint32_t)0x00000020) +#define RCC_APB2Periph_GPIOE ((uint32_t)0x00000040) +#define RCC_APB2Periph_GPIOF ((uint32_t)0x00000080) +#define RCC_APB2Periph_GPIOG ((uint32_t)0x00000100) +#define RCC_APB2Periph_ADC1 ((uint32_t)0x00000200) +#define RCC_APB2Periph_ADC2 ((uint32_t)0x00000400) +#define RCC_APB2Periph_TIM1 ((uint32_t)0x00000800) +#define RCC_APB2Periph_SPI1 ((uint32_t)0x00001000) +#define RCC_APB2Periph_TIM8 ((uint32_t)0x00002000) +#define RCC_APB2Periph_USART1 ((uint32_t)0x00004000) +#define RCC_APB2Periph_ADC3 ((uint32_t)0x00008000) +#define RCC_APB2Periph_TIM15 ((uint32_t)0x00010000) +#define RCC_APB2Periph_TIM16 ((uint32_t)0x00020000) +#define RCC_APB2Periph_TIM17 ((uint32_t)0x00040000) +#define RCC_APB2Periph_TIM9 ((uint32_t)0x00080000) +#define RCC_APB2Periph_TIM10 ((uint32_t)0x00100000) +#define RCC_APB2Periph_TIM11 ((uint32_t)0x00200000) + +#define IS_RCC_APB2_PERIPH(PERIPH) ((((PERIPH) & 0xFFC00002) == 0x00) && ((PERIPH) != 0x00)) +/** + * @} + */ + +/** @defgroup APB1_peripheral + * @{ + */ + +#define RCC_APB1Periph_TIM2 ((uint32_t)0x00000001) +#define RCC_APB1Periph_TIM3 ((uint32_t)0x00000002) +#define RCC_APB1Periph_TIM4 ((uint32_t)0x00000004) +#define RCC_APB1Periph_TIM5 ((uint32_t)0x00000008) +#define RCC_APB1Periph_TIM6 ((uint32_t)0x00000010) +#define RCC_APB1Periph_TIM7 ((uint32_t)0x00000020) +#define RCC_APB1Periph_TIM12 ((uint32_t)0x00000040) +#define RCC_APB1Periph_TIM13 ((uint32_t)0x00000080) +#define RCC_APB1Periph_TIM14 ((uint32_t)0x00000100) +#define RCC_APB1Periph_WWDG ((uint32_t)0x00000800) +#define RCC_APB1Periph_SPI2 ((uint32_t)0x00004000) +#define RCC_APB1Periph_SPI3 ((uint32_t)0x00008000) +#define RCC_APB1Periph_USART2 ((uint32_t)0x00020000) +#define RCC_APB1Periph_USART3 ((uint32_t)0x00040000) +#define RCC_APB1Periph_UART4 ((uint32_t)0x00080000) +#define RCC_APB1Periph_UART5 ((uint32_t)0x00100000) +#define RCC_APB1Periph_I2C1 ((uint32_t)0x00200000) +#define RCC_APB1Periph_I2C2 ((uint32_t)0x00400000) +#define RCC_APB1Periph_USB ((uint32_t)0x00800000) +#define RCC_APB1Periph_CAN1 ((uint32_t)0x02000000) +#define RCC_APB1Periph_CAN2 ((uint32_t)0x04000000) +#define RCC_APB1Periph_BKP ((uint32_t)0x08000000) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) +#define RCC_APB1Periph_DAC ((uint32_t)0x20000000) +#define RCC_APB1Periph_CEC ((uint32_t)0x40000000) + +#define IS_RCC_APB1_PERIPH(PERIPH) ((((PERIPH) & 0x81013600) == 0x00) && ((PERIPH) != 0x00)) + +/** + * @} + */ + +/** @defgroup Clock_source_to_output_on_MCO_pin + * @{ + */ + +#define RCC_MCO_NoClock ((uint8_t)0x00) +#define RCC_MCO_SYSCLK ((uint8_t)0x04) +#define RCC_MCO_HSI ((uint8_t)0x05) +#define RCC_MCO_HSE ((uint8_t)0x06) +#define RCC_MCO_PLLCLK_Div2 ((uint8_t)0x07) + +#ifndef STM32F10X_CL + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2)) +#else + #define RCC_MCO_PLL2CLK ((uint8_t)0x08) + #define RCC_MCO_PLL3CLK_Div2 ((uint8_t)0x09) + #define RCC_MCO_XT1 ((uint8_t)0x0A) + #define RCC_MCO_PLL3CLK ((uint8_t)0x0B) + + #define IS_RCC_MCO(MCO) (((MCO) == RCC_MCO_NoClock) || ((MCO) == RCC_MCO_HSI) || \ + ((MCO) == RCC_MCO_SYSCLK) || ((MCO) == RCC_MCO_HSE) || \ + ((MCO) == RCC_MCO_PLLCLK_Div2) || ((MCO) == RCC_MCO_PLL2CLK) || \ + ((MCO) == RCC_MCO_PLL3CLK_Div2) || ((MCO) == RCC_MCO_XT1) || \ + ((MCO) == RCC_MCO_PLL3CLK)) +#endif /* STM32F10X_CL */ + +/** + * @} + */ + +/** @defgroup RCC_Flag + * @{ + */ + +#define RCC_FLAG_HSIRDY ((uint8_t)0x21) +#define RCC_FLAG_HSERDY ((uint8_t)0x31) +#define RCC_FLAG_PLLRDY ((uint8_t)0x39) +#define RCC_FLAG_LSERDY ((uint8_t)0x41) +#define RCC_FLAG_LSIRDY ((uint8_t)0x61) +#define RCC_FLAG_PINRST ((uint8_t)0x7A) +#define RCC_FLAG_PORRST ((uint8_t)0x7B) +#define RCC_FLAG_SFTRST ((uint8_t)0x7C) +#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) +#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) +#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) + +#ifndef STM32F10X_CL + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#else + #define RCC_FLAG_PLL2RDY ((uint8_t)0x3B) + #define RCC_FLAG_PLL3RDY ((uint8_t)0x3D) + #define IS_RCC_FLAG(FLAG) (((FLAG) == RCC_FLAG_HSIRDY) || ((FLAG) == RCC_FLAG_HSERDY) || \ + ((FLAG) == RCC_FLAG_PLLRDY) || ((FLAG) == RCC_FLAG_LSERDY) || \ + ((FLAG) == RCC_FLAG_PLL2RDY) || ((FLAG) == RCC_FLAG_PLL3RDY) || \ + ((FLAG) == RCC_FLAG_LSIRDY) || ((FLAG) == RCC_FLAG_PINRST) || \ + ((FLAG) == RCC_FLAG_PORRST) || ((FLAG) == RCC_FLAG_SFTRST) || \ + ((FLAG) == RCC_FLAG_IWDGRST)|| ((FLAG) == RCC_FLAG_WWDGRST)|| \ + ((FLAG) == RCC_FLAG_LPWRRST)) +#endif /* STM32F10X_CL */ + +#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1F) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Exported_Functions + * @{ + */ + +void RCC_DeInit(void); +void RCC_HSEConfig(uint32_t RCC_HSE); +ErrorStatus RCC_WaitForHSEStartUp(void); +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue); +void RCC_HSICmd(FunctionalState NewState); +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul); +void RCC_PLLCmd(FunctionalState NewState); + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div); +#endif + +#ifdef STM32F10X_CL + void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div); + void RCC_PLL2Config(uint32_t RCC_PLL2Mul); + void RCC_PLL2Cmd(FunctionalState NewState); + void RCC_PLL3Config(uint32_t RCC_PLL3Mul); + void RCC_PLL3Cmd(FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource); +uint8_t RCC_GetSYSCLKSource(void); +void RCC_HCLKConfig(uint32_t RCC_SYSCLK); +void RCC_PCLK1Config(uint32_t RCC_HCLK); +void RCC_PCLK2Config(uint32_t RCC_HCLK); +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState); + +#ifndef STM32F10X_CL + void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource); +#else + void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource); +#endif /* STM32F10X_CL */ + +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2); + +#ifdef STM32F10X_CL + void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource); + void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource); +#endif /* STM32F10X_CL */ + +void RCC_LSEConfig(uint8_t RCC_LSE); +void RCC_LSICmd(FunctionalState NewState); +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource); +void RCC_RTCCLKCmd(FunctionalState NewState); +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks); +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); + +#ifdef STM32F10X_CL +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState); +#endif /* STM32F10X_CL */ + +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState); +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState); +void RCC_BackupResetCmd(FunctionalState NewState); +void RCC_ClockSecuritySystemCmd(FunctionalState NewState); +void RCC_MCOConfig(uint8_t RCC_MCO); +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG); +void RCC_ClearFlag(void); +ITStatus RCC_GetITStatus(uint8_t RCC_IT); +void RCC_ClearITPendingBit(uint8_t RCC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RCC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h new file mode 100755 index 0000000000..214a5893a0 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_rtc.h @@ -0,0 +1,135 @@ +/** + ****************************************************************************** + * @file stm32f10x_rtc.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the RTC firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_RTC_H +#define __STM32F10x_RTC_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup RTC + * @{ + */ + +/** @defgroup RTC_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Constants + * @{ + */ + +/** @defgroup RTC_interrupts_define + * @{ + */ + +#define RTC_IT_OW ((uint16_t)0x0004) /*!< Overflow interrupt */ +#define RTC_IT_ALR ((uint16_t)0x0002) /*!< Alarm interrupt */ +#define RTC_IT_SEC ((uint16_t)0x0001) /*!< Second interrupt */ +#define IS_RTC_IT(IT) ((((IT) & (uint16_t)0xFFF8) == 0x00) && ((IT) != 0x00)) +#define IS_RTC_GET_IT(IT) (((IT) == RTC_IT_OW) || ((IT) == RTC_IT_ALR) || \ + ((IT) == RTC_IT_SEC)) +/** + * @} + */ + +/** @defgroup RTC_interrupts_flags + * @{ + */ + +#define RTC_FLAG_RTOFF ((uint16_t)0x0020) /*!< RTC Operation OFF flag */ +#define RTC_FLAG_RSF ((uint16_t)0x0008) /*!< Registers Synchronized flag */ +#define RTC_FLAG_OW ((uint16_t)0x0004) /*!< Overflow flag */ +#define RTC_FLAG_ALR ((uint16_t)0x0002) /*!< Alarm flag */ +#define RTC_FLAG_SEC ((uint16_t)0x0001) /*!< Second flag */ +#define IS_RTC_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFFF0) == 0x00) && ((FLAG) != 0x00)) +#define IS_RTC_GET_FLAG(FLAG) (((FLAG) == RTC_FLAG_RTOFF) || ((FLAG) == RTC_FLAG_RSF) || \ + ((FLAG) == RTC_FLAG_OW) || ((FLAG) == RTC_FLAG_ALR) || \ + ((FLAG) == RTC_FLAG_SEC)) +#define IS_RTC_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFFFF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Exported_Functions + * @{ + */ + +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState); +void RTC_EnterConfigMode(void); +void RTC_ExitConfigMode(void); +uint32_t RTC_GetCounter(void); +void RTC_SetCounter(uint32_t CounterValue); +void RTC_SetPrescaler(uint32_t PrescalerValue); +void RTC_SetAlarm(uint32_t AlarmValue); +uint32_t RTC_GetDivider(void); +void RTC_WaitForLastTask(void); +void RTC_WaitForSynchro(void); +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG); +void RTC_ClearFlag(uint16_t RTC_FLAG); +ITStatus RTC_GetITStatus(uint16_t RTC_IT); +void RTC_ClearITPendingBit(uint16_t RTC_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_RTC_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h new file mode 100755 index 0000000000..40cfdedc30 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_sdio.h @@ -0,0 +1,531 @@ +/** + ****************************************************************************** + * @file stm32f10x_sdio.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the SDIO firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SDIO_H +#define __STM32F10x_SDIO_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SDIO + * @{ + */ + +/** @defgroup SDIO_Exported_Types + * @{ + */ + +typedef struct +{ + uint32_t SDIO_ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref SDIO_Clock_Edge */ + + uint32_t SDIO_ClockBypass; /*!< Specifies whether the SDIO Clock divider bypass is + enabled or disabled. + This parameter can be a value of @ref SDIO_Clock_Bypass */ + + uint32_t SDIO_ClockPowerSave; /*!< Specifies whether SDIO Clock output is enabled or + disabled when the bus is idle. + This parameter can be a value of @ref SDIO_Clock_Power_Save */ + + uint32_t SDIO_BusWide; /*!< Specifies the SDIO bus width. + This parameter can be a value of @ref SDIO_Bus_Wide */ + + uint32_t SDIO_HardwareFlowControl; /*!< Specifies whether the SDIO hardware flow control is enabled or disabled. + This parameter can be a value of @ref SDIO_Hardware_Flow_Control */ + + uint8_t SDIO_ClockDiv; /*!< Specifies the clock frequency of the SDIO controller. + This parameter can be a value between 0x00 and 0xFF. */ + +} SDIO_InitTypeDef; + +typedef struct +{ + uint32_t SDIO_Argument; /*!< Specifies the SDIO command argument which is sent + to a card as part of a command message. If a command + contains an argument, it must be loaded into this register + before writing the command to the command register */ + + uint32_t SDIO_CmdIndex; /*!< Specifies the SDIO command index. It must be lower than 0x40. */ + + uint32_t SDIO_Response; /*!< Specifies the SDIO response type. + This parameter can be a value of @ref SDIO_Response_Type */ + + uint32_t SDIO_Wait; /*!< Specifies whether SDIO wait-for-interrupt request is enabled or disabled. + This parameter can be a value of @ref SDIO_Wait_Interrupt_State */ + + uint32_t SDIO_CPSM; /*!< Specifies whether SDIO Command path state machine (CPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_CPSM_State */ +} SDIO_CmdInitTypeDef; + +typedef struct +{ + uint32_t SDIO_DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ + + uint32_t SDIO_DataLength; /*!< Specifies the number of data bytes to be transferred. */ + + uint32_t SDIO_DataBlockSize; /*!< Specifies the data block size for block transfer. + This parameter can be a value of @ref SDIO_Data_Block_Size */ + + uint32_t SDIO_TransferDir; /*!< Specifies the data transfer direction, whether the transfer + is a read or write. + This parameter can be a value of @ref SDIO_Transfer_Direction */ + + uint32_t SDIO_TransferMode; /*!< Specifies whether data transfer is in stream or block mode. + This parameter can be a value of @ref SDIO_Transfer_Type */ + + uint32_t SDIO_DPSM; /*!< Specifies whether SDIO Data path state machine (DPSM) + is enabled or disabled. + This parameter can be a value of @ref SDIO_DPSM_State */ +} SDIO_DataInitTypeDef; + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Constants + * @{ + */ + +/** @defgroup SDIO_Clock_Edge + * @{ + */ + +#define SDIO_ClockEdge_Rising ((uint32_t)0x00000000) +#define SDIO_ClockEdge_Falling ((uint32_t)0x00002000) +#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_ClockEdge_Rising) || \ + ((EDGE) == SDIO_ClockEdge_Falling)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Bypass + * @{ + */ + +#define SDIO_ClockBypass_Disable ((uint32_t)0x00000000) +#define SDIO_ClockBypass_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_ClockBypass_Disable) || \ + ((BYPASS) == SDIO_ClockBypass_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Clock_Power_Save + * @{ + */ + +#define SDIO_ClockPowerSave_Disable ((uint32_t)0x00000000) +#define SDIO_ClockPowerSave_Enable ((uint32_t)0x00000200) +#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_ClockPowerSave_Disable) || \ + ((SAVE) == SDIO_ClockPowerSave_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Bus_Wide + * @{ + */ + +#define SDIO_BusWide_1b ((uint32_t)0x00000000) +#define SDIO_BusWide_4b ((uint32_t)0x00000800) +#define SDIO_BusWide_8b ((uint32_t)0x00001000) +#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BusWide_1b) || ((WIDE) == SDIO_BusWide_4b) || \ + ((WIDE) == SDIO_BusWide_8b)) + +/** + * @} + */ + +/** @defgroup SDIO_Hardware_Flow_Control + * @{ + */ + +#define SDIO_HardwareFlowControl_Disable ((uint32_t)0x00000000) +#define SDIO_HardwareFlowControl_Enable ((uint32_t)0x00004000) +#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HardwareFlowControl_Disable) || \ + ((CONTROL) == SDIO_HardwareFlowControl_Enable)) +/** + * @} + */ + +/** @defgroup SDIO_Power_State + * @{ + */ + +#define SDIO_PowerState_OFF ((uint32_t)0x00000000) +#define SDIO_PowerState_ON ((uint32_t)0x00000003) +#define IS_SDIO_POWER_STATE(STATE) (((STATE) == SDIO_PowerState_OFF) || ((STATE) == SDIO_PowerState_ON)) +/** + * @} + */ + + +/** @defgroup SDIO_Interrupt_sources + * @{ + */ + +#define SDIO_IT_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_IT_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_IT_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_IT_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_IT_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_IT_RXOVERR ((uint32_t)0x00000020) +#define SDIO_IT_CMDREND ((uint32_t)0x00000040) +#define SDIO_IT_CMDSENT ((uint32_t)0x00000080) +#define SDIO_IT_DATAEND ((uint32_t)0x00000100) +#define SDIO_IT_STBITERR ((uint32_t)0x00000200) +#define SDIO_IT_DBCKEND ((uint32_t)0x00000400) +#define SDIO_IT_CMDACT ((uint32_t)0x00000800) +#define SDIO_IT_TXACT ((uint32_t)0x00001000) +#define SDIO_IT_RXACT ((uint32_t)0x00002000) +#define SDIO_IT_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_IT_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_IT_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_IT_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_IT_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_IT_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_IT_TXDAVL ((uint32_t)0x00100000) +#define SDIO_IT_RXDAVL ((uint32_t)0x00200000) +#define SDIO_IT_SDIOIT ((uint32_t)0x00400000) +#define SDIO_IT_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_IT(IT) ((((IT) & (uint32_t)0xFF000000) == 0x00) && ((IT) != (uint32_t)0x00)) +/** + * @} + */ + +/** @defgroup SDIO_Command_Index + * @{ + */ + +#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40) +/** + * @} + */ + +/** @defgroup SDIO_Response_Type + * @{ + */ + +#define SDIO_Response_No ((uint32_t)0x00000000) +#define SDIO_Response_Short ((uint32_t)0x00000040) +#define SDIO_Response_Long ((uint32_t)0x000000C0) +#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_Response_No) || \ + ((RESPONSE) == SDIO_Response_Short) || \ + ((RESPONSE) == SDIO_Response_Long)) +/** + * @} + */ + +/** @defgroup SDIO_Wait_Interrupt_State + * @{ + */ + +#define SDIO_Wait_No ((uint32_t)0x00000000) /*!< SDIO No Wait, TimeOut is enabled */ +#define SDIO_Wait_IT ((uint32_t)0x00000100) /*!< SDIO Wait Interrupt Request */ +#define SDIO_Wait_Pend ((uint32_t)0x00000200) /*!< SDIO Wait End of transfer */ +#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_Wait_No) || ((WAIT) == SDIO_Wait_IT) || \ + ((WAIT) == SDIO_Wait_Pend)) +/** + * @} + */ + +/** @defgroup SDIO_CPSM_State + * @{ + */ + +#define SDIO_CPSM_Disable ((uint32_t)0x00000000) +#define SDIO_CPSM_Enable ((uint32_t)0x00000400) +#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_Enable) || ((CPSM) == SDIO_CPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Response_Registers + * @{ + */ + +#define SDIO_RESP1 ((uint32_t)0x00000000) +#define SDIO_RESP2 ((uint32_t)0x00000004) +#define SDIO_RESP3 ((uint32_t)0x00000008) +#define SDIO_RESP4 ((uint32_t)0x0000000C) +#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || ((RESP) == SDIO_RESP2) || \ + ((RESP) == SDIO_RESP3) || ((RESP) == SDIO_RESP4)) +/** + * @} + */ + +/** @defgroup SDIO_Data_Length + * @{ + */ + +#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFF) +/** + * @} + */ + +/** @defgroup SDIO_Data_Block_Size + * @{ + */ + +#define SDIO_DataBlockSize_1b ((uint32_t)0x00000000) +#define SDIO_DataBlockSize_2b ((uint32_t)0x00000010) +#define SDIO_DataBlockSize_4b ((uint32_t)0x00000020) +#define SDIO_DataBlockSize_8b ((uint32_t)0x00000030) +#define SDIO_DataBlockSize_16b ((uint32_t)0x00000040) +#define SDIO_DataBlockSize_32b ((uint32_t)0x00000050) +#define SDIO_DataBlockSize_64b ((uint32_t)0x00000060) +#define SDIO_DataBlockSize_128b ((uint32_t)0x00000070) +#define SDIO_DataBlockSize_256b ((uint32_t)0x00000080) +#define SDIO_DataBlockSize_512b ((uint32_t)0x00000090) +#define SDIO_DataBlockSize_1024b ((uint32_t)0x000000A0) +#define SDIO_DataBlockSize_2048b ((uint32_t)0x000000B0) +#define SDIO_DataBlockSize_4096b ((uint32_t)0x000000C0) +#define SDIO_DataBlockSize_8192b ((uint32_t)0x000000D0) +#define SDIO_DataBlockSize_16384b ((uint32_t)0x000000E0) +#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DataBlockSize_1b) || \ + ((SIZE) == SDIO_DataBlockSize_2b) || \ + ((SIZE) == SDIO_DataBlockSize_4b) || \ + ((SIZE) == SDIO_DataBlockSize_8b) || \ + ((SIZE) == SDIO_DataBlockSize_16b) || \ + ((SIZE) == SDIO_DataBlockSize_32b) || \ + ((SIZE) == SDIO_DataBlockSize_64b) || \ + ((SIZE) == SDIO_DataBlockSize_128b) || \ + ((SIZE) == SDIO_DataBlockSize_256b) || \ + ((SIZE) == SDIO_DataBlockSize_512b) || \ + ((SIZE) == SDIO_DataBlockSize_1024b) || \ + ((SIZE) == SDIO_DataBlockSize_2048b) || \ + ((SIZE) == SDIO_DataBlockSize_4096b) || \ + ((SIZE) == SDIO_DataBlockSize_8192b) || \ + ((SIZE) == SDIO_DataBlockSize_16384b)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Direction + * @{ + */ + +#define SDIO_TransferDir_ToCard ((uint32_t)0x00000000) +#define SDIO_TransferDir_ToSDIO ((uint32_t)0x00000002) +#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TransferDir_ToCard) || \ + ((DIR) == SDIO_TransferDir_ToSDIO)) +/** + * @} + */ + +/** @defgroup SDIO_Transfer_Type + * @{ + */ + +#define SDIO_TransferMode_Block ((uint32_t)0x00000000) +#define SDIO_TransferMode_Stream ((uint32_t)0x00000004) +#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TransferMode_Stream) || \ + ((MODE) == SDIO_TransferMode_Block)) +/** + * @} + */ + +/** @defgroup SDIO_DPSM_State + * @{ + */ + +#define SDIO_DPSM_Disable ((uint32_t)0x00000000) +#define SDIO_DPSM_Enable ((uint32_t)0x00000001) +#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_Enable) || ((DPSM) == SDIO_DPSM_Disable)) +/** + * @} + */ + +/** @defgroup SDIO_Flags + * @{ + */ + +#define SDIO_FLAG_CCRCFAIL ((uint32_t)0x00000001) +#define SDIO_FLAG_DCRCFAIL ((uint32_t)0x00000002) +#define SDIO_FLAG_CTIMEOUT ((uint32_t)0x00000004) +#define SDIO_FLAG_DTIMEOUT ((uint32_t)0x00000008) +#define SDIO_FLAG_TXUNDERR ((uint32_t)0x00000010) +#define SDIO_FLAG_RXOVERR ((uint32_t)0x00000020) +#define SDIO_FLAG_CMDREND ((uint32_t)0x00000040) +#define SDIO_FLAG_CMDSENT ((uint32_t)0x00000080) +#define SDIO_FLAG_DATAEND ((uint32_t)0x00000100) +#define SDIO_FLAG_STBITERR ((uint32_t)0x00000200) +#define SDIO_FLAG_DBCKEND ((uint32_t)0x00000400) +#define SDIO_FLAG_CMDACT ((uint32_t)0x00000800) +#define SDIO_FLAG_TXACT ((uint32_t)0x00001000) +#define SDIO_FLAG_RXACT ((uint32_t)0x00002000) +#define SDIO_FLAG_TXFIFOHE ((uint32_t)0x00004000) +#define SDIO_FLAG_RXFIFOHF ((uint32_t)0x00008000) +#define SDIO_FLAG_TXFIFOF ((uint32_t)0x00010000) +#define SDIO_FLAG_RXFIFOF ((uint32_t)0x00020000) +#define SDIO_FLAG_TXFIFOE ((uint32_t)0x00040000) +#define SDIO_FLAG_RXFIFOE ((uint32_t)0x00080000) +#define SDIO_FLAG_TXDAVL ((uint32_t)0x00100000) +#define SDIO_FLAG_RXDAVL ((uint32_t)0x00200000) +#define SDIO_FLAG_SDIOIT ((uint32_t)0x00400000) +#define SDIO_FLAG_CEATAEND ((uint32_t)0x00800000) +#define IS_SDIO_FLAG(FLAG) (((FLAG) == SDIO_FLAG_CCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_DCRCFAIL) || \ + ((FLAG) == SDIO_FLAG_CTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_DTIMEOUT) || \ + ((FLAG) == SDIO_FLAG_TXUNDERR) || \ + ((FLAG) == SDIO_FLAG_RXOVERR) || \ + ((FLAG) == SDIO_FLAG_CMDREND) || \ + ((FLAG) == SDIO_FLAG_CMDSENT) || \ + ((FLAG) == SDIO_FLAG_DATAEND) || \ + ((FLAG) == SDIO_FLAG_STBITERR) || \ + ((FLAG) == SDIO_FLAG_DBCKEND) || \ + ((FLAG) == SDIO_FLAG_CMDACT) || \ + ((FLAG) == SDIO_FLAG_TXACT) || \ + ((FLAG) == SDIO_FLAG_RXACT) || \ + ((FLAG) == SDIO_FLAG_TXFIFOHE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOHF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOF) || \ + ((FLAG) == SDIO_FLAG_RXFIFOF) || \ + ((FLAG) == SDIO_FLAG_TXFIFOE) || \ + ((FLAG) == SDIO_FLAG_RXFIFOE) || \ + ((FLAG) == SDIO_FLAG_TXDAVL) || \ + ((FLAG) == SDIO_FLAG_RXDAVL) || \ + ((FLAG) == SDIO_FLAG_SDIOIT) || \ + ((FLAG) == SDIO_FLAG_CEATAEND)) + +#define IS_SDIO_CLEAR_FLAG(FLAG) ((((FLAG) & (uint32_t)0xFF3FF800) == 0x00) && ((FLAG) != (uint32_t)0x00)) + +#define IS_SDIO_GET_IT(IT) (((IT) == SDIO_IT_CCRCFAIL) || \ + ((IT) == SDIO_IT_DCRCFAIL) || \ + ((IT) == SDIO_IT_CTIMEOUT) || \ + ((IT) == SDIO_IT_DTIMEOUT) || \ + ((IT) == SDIO_IT_TXUNDERR) || \ + ((IT) == SDIO_IT_RXOVERR) || \ + ((IT) == SDIO_IT_CMDREND) || \ + ((IT) == SDIO_IT_CMDSENT) || \ + ((IT) == SDIO_IT_DATAEND) || \ + ((IT) == SDIO_IT_STBITERR) || \ + ((IT) == SDIO_IT_DBCKEND) || \ + ((IT) == SDIO_IT_CMDACT) || \ + ((IT) == SDIO_IT_TXACT) || \ + ((IT) == SDIO_IT_RXACT) || \ + ((IT) == SDIO_IT_TXFIFOHE) || \ + ((IT) == SDIO_IT_RXFIFOHF) || \ + ((IT) == SDIO_IT_TXFIFOF) || \ + ((IT) == SDIO_IT_RXFIFOF) || \ + ((IT) == SDIO_IT_TXFIFOE) || \ + ((IT) == SDIO_IT_RXFIFOE) || \ + ((IT) == SDIO_IT_TXDAVL) || \ + ((IT) == SDIO_IT_RXDAVL) || \ + ((IT) == SDIO_IT_SDIOIT) || \ + ((IT) == SDIO_IT_CEATAEND)) + +#define IS_SDIO_CLEAR_IT(IT) ((((IT) & (uint32_t)0xFF3FF800) == 0x00) && ((IT) != (uint32_t)0x00)) + +/** + * @} + */ + +/** @defgroup SDIO_Read_Wait_Mode + * @{ + */ + +#define SDIO_ReadWaitMode_CLK ((uint32_t)0x00000001) +#define SDIO_ReadWaitMode_DATA2 ((uint32_t)0x00000000) +#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_ReadWaitMode_CLK) || \ + ((MODE) == SDIO_ReadWaitMode_DATA2)) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Exported_Functions + * @{ + */ + +void SDIO_DeInit(void); +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct); +void SDIO_ClockCmd(FunctionalState NewState); +void SDIO_SetPowerState(uint32_t SDIO_PowerState); +uint32_t SDIO_GetPowerState(void); +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState); +void SDIO_DMACmd(FunctionalState NewState); +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct); +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct); +uint8_t SDIO_GetCommandResponse(void); +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP); +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct); +uint32_t SDIO_GetDataCounter(void); +uint32_t SDIO_ReadData(void); +void SDIO_WriteData(uint32_t Data); +uint32_t SDIO_GetFIFOCount(void); +void SDIO_StartSDIOReadWait(FunctionalState NewState); +void SDIO_StopSDIOReadWait(FunctionalState NewState); +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode); +void SDIO_SetSDIOOperation(FunctionalState NewState); +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState); +void SDIO_CommandCompletionCmd(FunctionalState NewState); +void SDIO_CEATAITCmd(FunctionalState NewState); +void SDIO_SendCEATACmd(FunctionalState NewState); +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG); +void SDIO_ClearFlag(uint32_t SDIO_FLAG); +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT); +void SDIO_ClearITPendingBit(uint32_t SDIO_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_SDIO_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h new file mode 100755 index 0000000000..6056c4c6ba --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_spi.h @@ -0,0 +1,487 @@ +/** + ****************************************************************************** + * @file stm32f10x_spi.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the SPI firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_SPI_H +#define __STM32F10x_SPI_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup SPI + * @{ + */ + +/** @defgroup SPI_Exported_Types + * @{ + */ + +/** + * @brief SPI Init structure definition + */ + +typedef struct +{ + uint16_t SPI_Direction; /*!< Specifies the SPI unidirectional or bidirectional data mode. + This parameter can be a value of @ref SPI_data_direction */ + + uint16_t SPI_Mode; /*!< Specifies the SPI operating mode. + This parameter can be a value of @ref SPI_mode */ + + uint16_t SPI_DataSize; /*!< Specifies the SPI data size. + This parameter can be a value of @ref SPI_data_size */ + + uint16_t SPI_CPOL; /*!< Specifies the serial clock steady state. + This parameter can be a value of @ref SPI_Clock_Polarity */ + + uint16_t SPI_CPHA; /*!< Specifies the clock active edge for the bit capture. + This parameter can be a value of @ref SPI_Clock_Phase */ + + uint16_t SPI_NSS; /*!< Specifies whether the NSS signal is managed by + hardware (NSS pin) or by software using the SSI bit. + This parameter can be a value of @ref SPI_Slave_Select_management */ + + uint16_t SPI_BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be + used to configure the transmit and receive SCK clock. + This parameter can be a value of @ref SPI_BaudRate_Prescaler. + @note The communication clock is derived from the master + clock. The slave clock does not need to be set. */ + + uint16_t SPI_FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. + This parameter can be a value of @ref SPI_MSB_LSB_transmission */ + + uint16_t SPI_CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. */ +}SPI_InitTypeDef; + +/** + * @brief I2S Init structure definition + */ + +typedef struct +{ + + uint16_t I2S_Mode; /*!< Specifies the I2S operating mode. + This parameter can be a value of @ref I2S_Mode */ + + uint16_t I2S_Standard; /*!< Specifies the standard used for the I2S communication. + This parameter can be a value of @ref I2S_Standard */ + + uint16_t I2S_DataFormat; /*!< Specifies the data format for the I2S communication. + This parameter can be a value of @ref I2S_Data_Format */ + + uint16_t I2S_MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. + This parameter can be a value of @ref I2S_MCLK_Output */ + + uint32_t I2S_AudioFreq; /*!< Specifies the frequency selected for the I2S communication. + This parameter can be a value of @ref I2S_Audio_Frequency */ + + uint16_t I2S_CPOL; /*!< Specifies the idle state of the I2S clock. + This parameter can be a value of @ref I2S_Clock_Polarity */ +}I2S_InitTypeDef; + +/** + * @} + */ + +/** @defgroup SPI_Exported_Constants + * @{ + */ + +#define IS_SPI_ALL_PERIPH(PERIPH) (((PERIPH) == SPI1) || \ + ((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +#define IS_SPI_23_PERIPH(PERIPH) (((PERIPH) == SPI2) || \ + ((PERIPH) == SPI3)) + +/** @defgroup SPI_data_direction + * @{ + */ + +#define SPI_Direction_2Lines_FullDuplex ((uint16_t)0x0000) +#define SPI_Direction_2Lines_RxOnly ((uint16_t)0x0400) +#define SPI_Direction_1Line_Rx ((uint16_t)0x8000) +#define SPI_Direction_1Line_Tx ((uint16_t)0xC000) +#define IS_SPI_DIRECTION_MODE(MODE) (((MODE) == SPI_Direction_2Lines_FullDuplex) || \ + ((MODE) == SPI_Direction_2Lines_RxOnly) || \ + ((MODE) == SPI_Direction_1Line_Rx) || \ + ((MODE) == SPI_Direction_1Line_Tx)) +/** + * @} + */ + +/** @defgroup SPI_mode + * @{ + */ + +#define SPI_Mode_Master ((uint16_t)0x0104) +#define SPI_Mode_Slave ((uint16_t)0x0000) +#define IS_SPI_MODE(MODE) (((MODE) == SPI_Mode_Master) || \ + ((MODE) == SPI_Mode_Slave)) +/** + * @} + */ + +/** @defgroup SPI_data_size + * @{ + */ + +#define SPI_DataSize_16b ((uint16_t)0x0800) +#define SPI_DataSize_8b ((uint16_t)0x0000) +#define IS_SPI_DATASIZE(DATASIZE) (((DATASIZE) == SPI_DataSize_16b) || \ + ((DATASIZE) == SPI_DataSize_8b)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Polarity + * @{ + */ + +#define SPI_CPOL_Low ((uint16_t)0x0000) +#define SPI_CPOL_High ((uint16_t)0x0002) +#define IS_SPI_CPOL(CPOL) (((CPOL) == SPI_CPOL_Low) || \ + ((CPOL) == SPI_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_Clock_Phase + * @{ + */ + +#define SPI_CPHA_1Edge ((uint16_t)0x0000) +#define SPI_CPHA_2Edge ((uint16_t)0x0001) +#define IS_SPI_CPHA(CPHA) (((CPHA) == SPI_CPHA_1Edge) || \ + ((CPHA) == SPI_CPHA_2Edge)) +/** + * @} + */ + +/** @defgroup SPI_Slave_Select_management + * @{ + */ + +#define SPI_NSS_Soft ((uint16_t)0x0200) +#define SPI_NSS_Hard ((uint16_t)0x0000) +#define IS_SPI_NSS(NSS) (((NSS) == SPI_NSS_Soft) || \ + ((NSS) == SPI_NSS_Hard)) +/** + * @} + */ + +/** @defgroup SPI_BaudRate_Prescaler + * @{ + */ + +#define SPI_BaudRatePrescaler_2 ((uint16_t)0x0000) +#define SPI_BaudRatePrescaler_4 ((uint16_t)0x0008) +#define SPI_BaudRatePrescaler_8 ((uint16_t)0x0010) +#define SPI_BaudRatePrescaler_16 ((uint16_t)0x0018) +#define SPI_BaudRatePrescaler_32 ((uint16_t)0x0020) +#define SPI_BaudRatePrescaler_64 ((uint16_t)0x0028) +#define SPI_BaudRatePrescaler_128 ((uint16_t)0x0030) +#define SPI_BaudRatePrescaler_256 ((uint16_t)0x0038) +#define IS_SPI_BAUDRATE_PRESCALER(PRESCALER) (((PRESCALER) == SPI_BaudRatePrescaler_2) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_4) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_8) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_16) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_32) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_64) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_128) || \ + ((PRESCALER) == SPI_BaudRatePrescaler_256)) +/** + * @} + */ + +/** @defgroup SPI_MSB_LSB_transmission + * @{ + */ + +#define SPI_FirstBit_MSB ((uint16_t)0x0000) +#define SPI_FirstBit_LSB ((uint16_t)0x0080) +#define IS_SPI_FIRST_BIT(BIT) (((BIT) == SPI_FirstBit_MSB) || \ + ((BIT) == SPI_FirstBit_LSB)) +/** + * @} + */ + +/** @defgroup I2S_Mode + * @{ + */ + +#define I2S_Mode_SlaveTx ((uint16_t)0x0000) +#define I2S_Mode_SlaveRx ((uint16_t)0x0100) +#define I2S_Mode_MasterTx ((uint16_t)0x0200) +#define I2S_Mode_MasterRx ((uint16_t)0x0300) +#define IS_I2S_MODE(MODE) (((MODE) == I2S_Mode_SlaveTx) || \ + ((MODE) == I2S_Mode_SlaveRx) || \ + ((MODE) == I2S_Mode_MasterTx) || \ + ((MODE) == I2S_Mode_MasterRx) ) +/** + * @} + */ + +/** @defgroup I2S_Standard + * @{ + */ + +#define I2S_Standard_Phillips ((uint16_t)0x0000) +#define I2S_Standard_MSB ((uint16_t)0x0010) +#define I2S_Standard_LSB ((uint16_t)0x0020) +#define I2S_Standard_PCMShort ((uint16_t)0x0030) +#define I2S_Standard_PCMLong ((uint16_t)0x00B0) +#define IS_I2S_STANDARD(STANDARD) (((STANDARD) == I2S_Standard_Phillips) || \ + ((STANDARD) == I2S_Standard_MSB) || \ + ((STANDARD) == I2S_Standard_LSB) || \ + ((STANDARD) == I2S_Standard_PCMShort) || \ + ((STANDARD) == I2S_Standard_PCMLong)) +/** + * @} + */ + +/** @defgroup I2S_Data_Format + * @{ + */ + +#define I2S_DataFormat_16b ((uint16_t)0x0000) +#define I2S_DataFormat_16bextended ((uint16_t)0x0001) +#define I2S_DataFormat_24b ((uint16_t)0x0003) +#define I2S_DataFormat_32b ((uint16_t)0x0005) +#define IS_I2S_DATA_FORMAT(FORMAT) (((FORMAT) == I2S_DataFormat_16b) || \ + ((FORMAT) == I2S_DataFormat_16bextended) || \ + ((FORMAT) == I2S_DataFormat_24b) || \ + ((FORMAT) == I2S_DataFormat_32b)) +/** + * @} + */ + +/** @defgroup I2S_MCLK_Output + * @{ + */ + +#define I2S_MCLKOutput_Enable ((uint16_t)0x0200) +#define I2S_MCLKOutput_Disable ((uint16_t)0x0000) +#define IS_I2S_MCLK_OUTPUT(OUTPUT) (((OUTPUT) == I2S_MCLKOutput_Enable) || \ + ((OUTPUT) == I2S_MCLKOutput_Disable)) +/** + * @} + */ + +/** @defgroup I2S_Audio_Frequency + * @{ + */ + +#define I2S_AudioFreq_192k ((uint32_t)192000) +#define I2S_AudioFreq_96k ((uint32_t)96000) +#define I2S_AudioFreq_48k ((uint32_t)48000) +#define I2S_AudioFreq_44k ((uint32_t)44100) +#define I2S_AudioFreq_32k ((uint32_t)32000) +#define I2S_AudioFreq_22k ((uint32_t)22050) +#define I2S_AudioFreq_16k ((uint32_t)16000) +#define I2S_AudioFreq_11k ((uint32_t)11025) +#define I2S_AudioFreq_8k ((uint32_t)8000) +#define I2S_AudioFreq_Default ((uint32_t)2) + +#define IS_I2S_AUDIO_FREQ(FREQ) ((((FREQ) >= I2S_AudioFreq_8k) && \ + ((FREQ) <= I2S_AudioFreq_192k)) || \ + ((FREQ) == I2S_AudioFreq_Default)) +/** + * @} + */ + +/** @defgroup I2S_Clock_Polarity + * @{ + */ + +#define I2S_CPOL_Low ((uint16_t)0x0000) +#define I2S_CPOL_High ((uint16_t)0x0008) +#define IS_I2S_CPOL(CPOL) (((CPOL) == I2S_CPOL_Low) || \ + ((CPOL) == I2S_CPOL_High)) +/** + * @} + */ + +/** @defgroup SPI_I2S_DMA_transfer_requests + * @{ + */ + +#define SPI_I2S_DMAReq_Tx ((uint16_t)0x0002) +#define SPI_I2S_DMAReq_Rx ((uint16_t)0x0001) +#define IS_SPI_I2S_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFFFC) == 0x00) && ((DMAREQ) != 0x00)) +/** + * @} + */ + +/** @defgroup SPI_NSS_internal_software_management + * @{ + */ + +#define SPI_NSSInternalSoft_Set ((uint16_t)0x0100) +#define SPI_NSSInternalSoft_Reset ((uint16_t)0xFEFF) +#define IS_SPI_NSS_INTERNAL(INTERNAL) (((INTERNAL) == SPI_NSSInternalSoft_Set) || \ + ((INTERNAL) == SPI_NSSInternalSoft_Reset)) +/** + * @} + */ + +/** @defgroup SPI_CRC_Transmit_Receive + * @{ + */ + +#define SPI_CRC_Tx ((uint8_t)0x00) +#define SPI_CRC_Rx ((uint8_t)0x01) +#define IS_SPI_CRC(CRC) (((CRC) == SPI_CRC_Tx) || ((CRC) == SPI_CRC_Rx)) +/** + * @} + */ + +/** @defgroup SPI_direction_transmit_receive + * @{ + */ + +#define SPI_Direction_Rx ((uint16_t)0xBFFF) +#define SPI_Direction_Tx ((uint16_t)0x4000) +#define IS_SPI_DIRECTION(DIRECTION) (((DIRECTION) == SPI_Direction_Rx) || \ + ((DIRECTION) == SPI_Direction_Tx)) +/** + * @} + */ + +/** @defgroup SPI_I2S_interrupts_definition + * @{ + */ + +#define SPI_I2S_IT_TXE ((uint8_t)0x71) +#define SPI_I2S_IT_RXNE ((uint8_t)0x60) +#define SPI_I2S_IT_ERR ((uint8_t)0x50) +#define IS_SPI_I2S_CONFIG_IT(IT) (((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == SPI_I2S_IT_RXNE) || \ + ((IT) == SPI_I2S_IT_ERR)) +#define SPI_I2S_IT_OVR ((uint8_t)0x56) +#define SPI_IT_MODF ((uint8_t)0x55) +#define SPI_IT_CRCERR ((uint8_t)0x54) +#define I2S_IT_UDR ((uint8_t)0x53) +#define IS_SPI_I2S_CLEAR_IT(IT) (((IT) == SPI_IT_CRCERR)) +#define IS_SPI_I2S_GET_IT(IT) (((IT) == SPI_I2S_IT_RXNE) || ((IT) == SPI_I2S_IT_TXE) || \ + ((IT) == I2S_IT_UDR) || ((IT) == SPI_IT_CRCERR) || \ + ((IT) == SPI_IT_MODF) || ((IT) == SPI_I2S_IT_OVR)) +/** + * @} + */ + +/** @defgroup SPI_I2S_flags_definition + * @{ + */ + +#define SPI_I2S_FLAG_RXNE ((uint16_t)0x0001) +#define SPI_I2S_FLAG_TXE ((uint16_t)0x0002) +#define I2S_FLAG_CHSIDE ((uint16_t)0x0004) +#define I2S_FLAG_UDR ((uint16_t)0x0008) +#define SPI_FLAG_CRCERR ((uint16_t)0x0010) +#define SPI_FLAG_MODF ((uint16_t)0x0020) +#define SPI_I2S_FLAG_OVR ((uint16_t)0x0040) +#define SPI_I2S_FLAG_BSY ((uint16_t)0x0080) +#define IS_SPI_I2S_CLEAR_FLAG(FLAG) (((FLAG) == SPI_FLAG_CRCERR)) +#define IS_SPI_I2S_GET_FLAG(FLAG) (((FLAG) == SPI_I2S_FLAG_BSY) || ((FLAG) == SPI_I2S_FLAG_OVR) || \ + ((FLAG) == SPI_FLAG_MODF) || ((FLAG) == SPI_FLAG_CRCERR) || \ + ((FLAG) == I2S_FLAG_UDR) || ((FLAG) == I2S_FLAG_CHSIDE) || \ + ((FLAG) == SPI_I2S_FLAG_TXE) || ((FLAG) == SPI_I2S_FLAG_RXNE)) +/** + * @} + */ + +/** @defgroup SPI_CRC_polynomial + * @{ + */ + +#define IS_SPI_CRC_POLYNOMIAL(POLYNOMIAL) ((POLYNOMIAL) >= 0x1) +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Exported_Functions + * @{ + */ + +void SPI_I2S_DeInit(SPI_TypeDef* SPIx); +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct); +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct); +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct); +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct); +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState); +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState); +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data); +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx); +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft); +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState); +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize); +void SPI_TransmitCRC(SPI_TypeDef* SPIx); +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState); +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC); +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx); +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction); +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG); +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_SPI_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h new file mode 100755 index 0000000000..cd7ac3e9c7 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h @@ -0,0 +1,1164 @@ +/** + ****************************************************************************** + * @file stm32f10x_tim.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the TIM firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_TIM_H +#define __STM32F10x_TIM_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup TIM + * @{ + */ + +/** @defgroup TIM_Exported_Types + * @{ + */ + +/** + * @brief TIM Time Base Init structure definition + * @note This structure is used with all TIMx except for TIM6 and TIM7. + */ + +typedef struct +{ + uint16_t TIM_Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_CounterMode; /*!< Specifies the counter mode. + This parameter can be a value of @ref TIM_Counter_Mode */ + + uint16_t TIM_Period; /*!< Specifies the period value to be loaded into the active + Auto-Reload Register at the next update event. + This parameter must be a number between 0x0000 and 0xFFFF. */ + + uint16_t TIM_ClockDivision; /*!< Specifies the clock division. + This parameter can be a value of @ref TIM_Clock_Division_CKD */ + + uint8_t TIM_RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter + reaches zero, an update event is generated and counting restarts + from the RCR value (N). + This means in PWM mode that (N+1) corresponds to: + - the number of PWM periods in edge-aligned mode + - the number of half PWM period in center-aligned mode + This parameter must be a number between 0x00 and 0xFF. + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_TimeBaseInitTypeDef; + +/** + * @brief TIM Output Compare Init structure definition + */ + +typedef struct +{ + uint16_t TIM_OCMode; /*!< Specifies the TIM mode. + This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ + + uint16_t TIM_OutputState; /*!< Specifies the TIM Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_state */ + + uint16_t TIM_OutputNState; /*!< Specifies the TIM complementary Output Compare state. + This parameter can be a value of @ref TIM_Output_Compare_N_state + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. + This parameter can be a number between 0x0000 and 0xFFFF */ + + uint16_t TIM_OCPolarity; /*!< Specifies the output polarity. + This parameter can be a value of @ref TIM_Output_Compare_Polarity */ + + uint16_t TIM_OCNPolarity; /*!< Specifies the complementary output polarity. + This parameter can be a value of @ref TIM_Output_Compare_N_Polarity + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ + + uint16_t TIM_OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. + This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State + @note This parameter is valid only for TIM1 and TIM8. */ +} TIM_OCInitTypeDef; + +/** + * @brief TIM Input Capture Init structure definition + */ + +typedef struct +{ + + uint16_t TIM_Channel; /*!< Specifies the TIM channel. + This parameter can be a value of @ref TIM_Channel */ + + uint16_t TIM_ICPolarity; /*!< Specifies the active edge of the input signal. + This parameter can be a value of @ref TIM_Input_Capture_Polarity */ + + uint16_t TIM_ICSelection; /*!< Specifies the input. + This parameter can be a value of @ref TIM_Input_Capture_Selection */ + + uint16_t TIM_ICPrescaler; /*!< Specifies the Input Capture Prescaler. + This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ + + uint16_t TIM_ICFilter; /*!< Specifies the input capture filter. + This parameter can be a number between 0x0 and 0xF */ +} TIM_ICInitTypeDef; + +/** + * @brief BDTR structure definition + * @note This structure is used only with TIM1 and TIM8. + */ + +typedef struct +{ + + uint16_t TIM_OSSRState; /*!< Specifies the Off-State selection used in Run mode. + This parameter can be a value of @ref OSSR_Off_State_Selection_for_Run_mode_state */ + + uint16_t TIM_OSSIState; /*!< Specifies the Off-State used in Idle state. + This parameter can be a value of @ref OSSI_Off_State_Selection_for_Idle_mode_state */ + + uint16_t TIM_LOCKLevel; /*!< Specifies the LOCK level parameters. + This parameter can be a value of @ref Lock_level */ + + uint16_t TIM_DeadTime; /*!< Specifies the delay time between the switching-off and the + switching-on of the outputs. + This parameter can be a number between 0x00 and 0xFF */ + + uint16_t TIM_Break; /*!< Specifies whether the TIM Break input is enabled or not. + This parameter can be a value of @ref Break_Input_enable_disable */ + + uint16_t TIM_BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. + This parameter can be a value of @ref Break_Polarity */ + + uint16_t TIM_AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. + This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ +} TIM_BDTRInitTypeDef; + +/** @defgroup TIM_Exported_constants + * @{ + */ + +#define IS_TIM_ALL_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST1: TIM 1 and 8 */ +#define IS_TIM_LIST1_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8)) + +/* LIST2: TIM 1, 8, 15 16 and 17 */ +#define IS_TIM_LIST2_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST3: TIM 1, 2, 3, 4, 5 and 8 */ +#define IS_TIM_LIST3_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8)) + +/* LIST4: TIM 1, 2, 3, 4, 5, 8, 15, 16 and 17 */ +#define IS_TIM_LIST4_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST5: TIM 1, 2, 3, 4, 5, 8 and 15 */ +#define IS_TIM_LIST5_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)) + +/* LIST6: TIM 1, 2, 3, 4, 5, 8, 9, 12 and 15 */ +#define IS_TIM_LIST6_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST7: TIM 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 and 15 */ +#define IS_TIM_LIST7_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM15)) + +/* LIST8: TIM 1, 2, 3, 4, 5, 8, 9, 10, 11, 12, 13, 14, 15, 16 and 17 */ +#define IS_TIM_LIST8_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM9) || \ + ((PERIPH) == TIM10)|| \ + ((PERIPH) == TIM11)|| \ + ((PERIPH) == TIM12)|| \ + ((PERIPH) == TIM13)|| \ + ((PERIPH) == TIM14)|| \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/* LIST9: TIM 1, 2, 3, 4, 5, 6, 7, 8, 15, 16, and 17 */ +#define IS_TIM_LIST9_PERIPH(PERIPH) (((PERIPH) == TIM1) || \ + ((PERIPH) == TIM2) || \ + ((PERIPH) == TIM3) || \ + ((PERIPH) == TIM4) || \ + ((PERIPH) == TIM5) || \ + ((PERIPH) == TIM6) || \ + ((PERIPH) == TIM7) || \ + ((PERIPH) == TIM8) || \ + ((PERIPH) == TIM15)|| \ + ((PERIPH) == TIM16)|| \ + ((PERIPH) == TIM17)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_and_PWM_modes + * @{ + */ + +#define TIM_OCMode_Timing ((uint16_t)0x0000) +#define TIM_OCMode_Active ((uint16_t)0x0010) +#define TIM_OCMode_Inactive ((uint16_t)0x0020) +#define TIM_OCMode_Toggle ((uint16_t)0x0030) +#define TIM_OCMode_PWM1 ((uint16_t)0x0060) +#define TIM_OCMode_PWM2 ((uint16_t)0x0070) +#define IS_TIM_OC_MODE(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2)) +#define IS_TIM_OCM(MODE) (((MODE) == TIM_OCMode_Timing) || \ + ((MODE) == TIM_OCMode_Active) || \ + ((MODE) == TIM_OCMode_Inactive) || \ + ((MODE) == TIM_OCMode_Toggle)|| \ + ((MODE) == TIM_OCMode_PWM1) || \ + ((MODE) == TIM_OCMode_PWM2) || \ + ((MODE) == TIM_ForcedAction_Active) || \ + ((MODE) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_One_Pulse_Mode + * @{ + */ + +#define TIM_OPMode_Single ((uint16_t)0x0008) +#define TIM_OPMode_Repetitive ((uint16_t)0x0000) +#define IS_TIM_OPM_MODE(MODE) (((MODE) == TIM_OPMode_Single) || \ + ((MODE) == TIM_OPMode_Repetitive)) +/** + * @} + */ + +/** @defgroup TIM_Channel + * @{ + */ + +#define TIM_Channel_1 ((uint16_t)0x0000) +#define TIM_Channel_2 ((uint16_t)0x0004) +#define TIM_Channel_3 ((uint16_t)0x0008) +#define TIM_Channel_4 ((uint16_t)0x000C) +#define IS_TIM_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3) || \ + ((CHANNEL) == TIM_Channel_4)) +#define IS_TIM_PWMI_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2)) +#define IS_TIM_COMPLEMENTARY_CHANNEL(CHANNEL) (((CHANNEL) == TIM_Channel_1) || \ + ((CHANNEL) == TIM_Channel_2) || \ + ((CHANNEL) == TIM_Channel_3)) +/** + * @} + */ + +/** @defgroup TIM_Clock_Division_CKD + * @{ + */ + +#define TIM_CKD_DIV1 ((uint16_t)0x0000) +#define TIM_CKD_DIV2 ((uint16_t)0x0100) +#define TIM_CKD_DIV4 ((uint16_t)0x0200) +#define IS_TIM_CKD_DIV(DIV) (((DIV) == TIM_CKD_DIV1) || \ + ((DIV) == TIM_CKD_DIV2) || \ + ((DIV) == TIM_CKD_DIV4)) +/** + * @} + */ + +/** @defgroup TIM_Counter_Mode + * @{ + */ + +#define TIM_CounterMode_Up ((uint16_t)0x0000) +#define TIM_CounterMode_Down ((uint16_t)0x0010) +#define TIM_CounterMode_CenterAligned1 ((uint16_t)0x0020) +#define TIM_CounterMode_CenterAligned2 ((uint16_t)0x0040) +#define TIM_CounterMode_CenterAligned3 ((uint16_t)0x0060) +#define IS_TIM_COUNTER_MODE(MODE) (((MODE) == TIM_CounterMode_Up) || \ + ((MODE) == TIM_CounterMode_Down) || \ + ((MODE) == TIM_CounterMode_CenterAligned1) || \ + ((MODE) == TIM_CounterMode_CenterAligned2) || \ + ((MODE) == TIM_CounterMode_CenterAligned3)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Polarity + * @{ + */ + +#define TIM_OCPolarity_High ((uint16_t)0x0000) +#define TIM_OCPolarity_Low ((uint16_t)0x0002) +#define IS_TIM_OC_POLARITY(POLARITY) (((POLARITY) == TIM_OCPolarity_High) || \ + ((POLARITY) == TIM_OCPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Polarity + * @{ + */ + +#define TIM_OCNPolarity_High ((uint16_t)0x0000) +#define TIM_OCNPolarity_Low ((uint16_t)0x0008) +#define IS_TIM_OCN_POLARITY(POLARITY) (((POLARITY) == TIM_OCNPolarity_High) || \ + ((POLARITY) == TIM_OCNPolarity_Low)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_state + * @{ + */ + +#define TIM_OutputState_Disable ((uint16_t)0x0000) +#define TIM_OutputState_Enable ((uint16_t)0x0001) +#define IS_TIM_OUTPUT_STATE(STATE) (((STATE) == TIM_OutputState_Disable) || \ + ((STATE) == TIM_OutputState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_state + * @{ + */ + +#define TIM_OutputNState_Disable ((uint16_t)0x0000) +#define TIM_OutputNState_Enable ((uint16_t)0x0004) +#define IS_TIM_OUTPUTN_STATE(STATE) (((STATE) == TIM_OutputNState_Disable) || \ + ((STATE) == TIM_OutputNState_Enable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_state + * @{ + */ + +#define TIM_CCx_Enable ((uint16_t)0x0001) +#define TIM_CCx_Disable ((uint16_t)0x0000) +#define IS_TIM_CCX(CCX) (((CCX) == TIM_CCx_Enable) || \ + ((CCX) == TIM_CCx_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Capture_Compare_N_state + * @{ + */ + +#define TIM_CCxN_Enable ((uint16_t)0x0004) +#define TIM_CCxN_Disable ((uint16_t)0x0000) +#define IS_TIM_CCXN(CCXN) (((CCXN) == TIM_CCxN_Enable) || \ + ((CCXN) == TIM_CCxN_Disable)) +/** + * @} + */ + +/** @defgroup Break_Input_enable_disable + * @{ + */ + +#define TIM_Break_Enable ((uint16_t)0x1000) +#define TIM_Break_Disable ((uint16_t)0x0000) +#define IS_TIM_BREAK_STATE(STATE) (((STATE) == TIM_Break_Enable) || \ + ((STATE) == TIM_Break_Disable)) +/** + * @} + */ + +/** @defgroup Break_Polarity + * @{ + */ + +#define TIM_BreakPolarity_Low ((uint16_t)0x0000) +#define TIM_BreakPolarity_High ((uint16_t)0x2000) +#define IS_TIM_BREAK_POLARITY(POLARITY) (((POLARITY) == TIM_BreakPolarity_Low) || \ + ((POLARITY) == TIM_BreakPolarity_High)) +/** + * @} + */ + +/** @defgroup TIM_AOE_Bit_Set_Reset + * @{ + */ + +#define TIM_AutomaticOutput_Enable ((uint16_t)0x4000) +#define TIM_AutomaticOutput_Disable ((uint16_t)0x0000) +#define IS_TIM_AUTOMATIC_OUTPUT_STATE(STATE) (((STATE) == TIM_AutomaticOutput_Enable) || \ + ((STATE) == TIM_AutomaticOutput_Disable)) +/** + * @} + */ + +/** @defgroup Lock_level + * @{ + */ + +#define TIM_LOCKLevel_OFF ((uint16_t)0x0000) +#define TIM_LOCKLevel_1 ((uint16_t)0x0100) +#define TIM_LOCKLevel_2 ((uint16_t)0x0200) +#define TIM_LOCKLevel_3 ((uint16_t)0x0300) +#define IS_TIM_LOCK_LEVEL(LEVEL) (((LEVEL) == TIM_LOCKLevel_OFF) || \ + ((LEVEL) == TIM_LOCKLevel_1) || \ + ((LEVEL) == TIM_LOCKLevel_2) || \ + ((LEVEL) == TIM_LOCKLevel_3)) +/** + * @} + */ + +/** @defgroup OSSI_Off_State_Selection_for_Idle_mode_state + * @{ + */ + +#define TIM_OSSIState_Enable ((uint16_t)0x0400) +#define TIM_OSSIState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSI_STATE(STATE) (((STATE) == TIM_OSSIState_Enable) || \ + ((STATE) == TIM_OSSIState_Disable)) +/** + * @} + */ + +/** @defgroup OSSR_Off_State_Selection_for_Run_mode_state + * @{ + */ + +#define TIM_OSSRState_Enable ((uint16_t)0x0800) +#define TIM_OSSRState_Disable ((uint16_t)0x0000) +#define IS_TIM_OSSR_STATE(STATE) (((STATE) == TIM_OSSRState_Enable) || \ + ((STATE) == TIM_OSSRState_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Idle_State + * @{ + */ + +#define TIM_OCIdleState_Set ((uint16_t)0x0100) +#define TIM_OCIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCIDLE_STATE(STATE) (((STATE) == TIM_OCIdleState_Set) || \ + ((STATE) == TIM_OCIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_N_Idle_State + * @{ + */ + +#define TIM_OCNIdleState_Set ((uint16_t)0x0200) +#define TIM_OCNIdleState_Reset ((uint16_t)0x0000) +#define IS_TIM_OCNIDLE_STATE(STATE) (((STATE) == TIM_OCNIdleState_Set) || \ + ((STATE) == TIM_OCNIdleState_Reset)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Polarity + * @{ + */ + +#define TIM_ICPolarity_Rising ((uint16_t)0x0000) +#define TIM_ICPolarity_Falling ((uint16_t)0x0002) +#define TIM_ICPolarity_BothEdge ((uint16_t)0x000A) +#define IS_TIM_IC_POLARITY(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)) +#define IS_TIM_IC_POLARITY_LITE(POLARITY) (((POLARITY) == TIM_ICPolarity_Rising) || \ + ((POLARITY) == TIM_ICPolarity_Falling)|| \ + ((POLARITY) == TIM_ICPolarity_BothEdge)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Selection + * @{ + */ + +#define TIM_ICSelection_DirectTI ((uint16_t)0x0001) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC1, IC2, IC3 or IC4, respectively */ +#define TIM_ICSelection_IndirectTI ((uint16_t)0x0002) /*!< TIM Input 1, 2, 3 or 4 is selected to be + connected to IC2, IC1, IC4 or IC3, respectively. */ +#define TIM_ICSelection_TRC ((uint16_t)0x0003) /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC. */ +#define IS_TIM_IC_SELECTION(SELECTION) (((SELECTION) == TIM_ICSelection_DirectTI) || \ + ((SELECTION) == TIM_ICSelection_IndirectTI) || \ + ((SELECTION) == TIM_ICSelection_TRC)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Prescaler + * @{ + */ + +#define TIM_ICPSC_DIV1 ((uint16_t)0x0000) /*!< Capture performed each time an edge is detected on the capture input. */ +#define TIM_ICPSC_DIV2 ((uint16_t)0x0004) /*!< Capture performed once every 2 events. */ +#define TIM_ICPSC_DIV4 ((uint16_t)0x0008) /*!< Capture performed once every 4 events. */ +#define TIM_ICPSC_DIV8 ((uint16_t)0x000C) /*!< Capture performed once every 8 events. */ +#define IS_TIM_IC_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ICPSC_DIV1) || \ + ((PRESCALER) == TIM_ICPSC_DIV2) || \ + ((PRESCALER) == TIM_ICPSC_DIV4) || \ + ((PRESCALER) == TIM_ICPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_interrupt_sources + * @{ + */ + +#define TIM_IT_Update ((uint16_t)0x0001) +#define TIM_IT_CC1 ((uint16_t)0x0002) +#define TIM_IT_CC2 ((uint16_t)0x0004) +#define TIM_IT_CC3 ((uint16_t)0x0008) +#define TIM_IT_CC4 ((uint16_t)0x0010) +#define TIM_IT_COM ((uint16_t)0x0020) +#define TIM_IT_Trigger ((uint16_t)0x0040) +#define TIM_IT_Break ((uint16_t)0x0080) +#define IS_TIM_IT(IT) ((((IT) & (uint16_t)0xFF00) == 0x0000) && ((IT) != 0x0000)) + +#define IS_TIM_GET_IT(IT) (((IT) == TIM_IT_Update) || \ + ((IT) == TIM_IT_CC1) || \ + ((IT) == TIM_IT_CC2) || \ + ((IT) == TIM_IT_CC3) || \ + ((IT) == TIM_IT_CC4) || \ + ((IT) == TIM_IT_COM) || \ + ((IT) == TIM_IT_Trigger) || \ + ((IT) == TIM_IT_Break)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Base_address + * @{ + */ + +#define TIM_DMABase_CR1 ((uint16_t)0x0000) +#define TIM_DMABase_CR2 ((uint16_t)0x0001) +#define TIM_DMABase_SMCR ((uint16_t)0x0002) +#define TIM_DMABase_DIER ((uint16_t)0x0003) +#define TIM_DMABase_SR ((uint16_t)0x0004) +#define TIM_DMABase_EGR ((uint16_t)0x0005) +#define TIM_DMABase_CCMR1 ((uint16_t)0x0006) +#define TIM_DMABase_CCMR2 ((uint16_t)0x0007) +#define TIM_DMABase_CCER ((uint16_t)0x0008) +#define TIM_DMABase_CNT ((uint16_t)0x0009) +#define TIM_DMABase_PSC ((uint16_t)0x000A) +#define TIM_DMABase_ARR ((uint16_t)0x000B) +#define TIM_DMABase_RCR ((uint16_t)0x000C) +#define TIM_DMABase_CCR1 ((uint16_t)0x000D) +#define TIM_DMABase_CCR2 ((uint16_t)0x000E) +#define TIM_DMABase_CCR3 ((uint16_t)0x000F) +#define TIM_DMABase_CCR4 ((uint16_t)0x0010) +#define TIM_DMABase_BDTR ((uint16_t)0x0011) +#define TIM_DMABase_DCR ((uint16_t)0x0012) +#define IS_TIM_DMA_BASE(BASE) (((BASE) == TIM_DMABase_CR1) || \ + ((BASE) == TIM_DMABase_CR2) || \ + ((BASE) == TIM_DMABase_SMCR) || \ + ((BASE) == TIM_DMABase_DIER) || \ + ((BASE) == TIM_DMABase_SR) || \ + ((BASE) == TIM_DMABase_EGR) || \ + ((BASE) == TIM_DMABase_CCMR1) || \ + ((BASE) == TIM_DMABase_CCMR2) || \ + ((BASE) == TIM_DMABase_CCER) || \ + ((BASE) == TIM_DMABase_CNT) || \ + ((BASE) == TIM_DMABase_PSC) || \ + ((BASE) == TIM_DMABase_ARR) || \ + ((BASE) == TIM_DMABase_RCR) || \ + ((BASE) == TIM_DMABase_CCR1) || \ + ((BASE) == TIM_DMABase_CCR2) || \ + ((BASE) == TIM_DMABase_CCR3) || \ + ((BASE) == TIM_DMABase_CCR4) || \ + ((BASE) == TIM_DMABase_BDTR) || \ + ((BASE) == TIM_DMABase_DCR)) +/** + * @} + */ + +/** @defgroup TIM_DMA_Burst_Length + * @{ + */ + +#define TIM_DMABurstLength_1Transfer ((uint16_t)0x0000) +#define TIM_DMABurstLength_2Transfers ((uint16_t)0x0100) +#define TIM_DMABurstLength_3Transfers ((uint16_t)0x0200) +#define TIM_DMABurstLength_4Transfers ((uint16_t)0x0300) +#define TIM_DMABurstLength_5Transfers ((uint16_t)0x0400) +#define TIM_DMABurstLength_6Transfers ((uint16_t)0x0500) +#define TIM_DMABurstLength_7Transfers ((uint16_t)0x0600) +#define TIM_DMABurstLength_8Transfers ((uint16_t)0x0700) +#define TIM_DMABurstLength_9Transfers ((uint16_t)0x0800) +#define TIM_DMABurstLength_10Transfers ((uint16_t)0x0900) +#define TIM_DMABurstLength_11Transfers ((uint16_t)0x0A00) +#define TIM_DMABurstLength_12Transfers ((uint16_t)0x0B00) +#define TIM_DMABurstLength_13Transfers ((uint16_t)0x0C00) +#define TIM_DMABurstLength_14Transfers ((uint16_t)0x0D00) +#define TIM_DMABurstLength_15Transfers ((uint16_t)0x0E00) +#define TIM_DMABurstLength_16Transfers ((uint16_t)0x0F00) +#define TIM_DMABurstLength_17Transfers ((uint16_t)0x1000) +#define TIM_DMABurstLength_18Transfers ((uint16_t)0x1100) +#define IS_TIM_DMA_LENGTH(LENGTH) (((LENGTH) == TIM_DMABurstLength_1Transfer) || \ + ((LENGTH) == TIM_DMABurstLength_2Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_3Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_4Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_5Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_6Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_7Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_8Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_9Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_10Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_11Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_12Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_13Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_14Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_15Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_16Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_17Transfers) || \ + ((LENGTH) == TIM_DMABurstLength_18Transfers)) +/** + * @} + */ + +/** @defgroup TIM_DMA_sources + * @{ + */ + +#define TIM_DMA_Update ((uint16_t)0x0100) +#define TIM_DMA_CC1 ((uint16_t)0x0200) +#define TIM_DMA_CC2 ((uint16_t)0x0400) +#define TIM_DMA_CC3 ((uint16_t)0x0800) +#define TIM_DMA_CC4 ((uint16_t)0x1000) +#define TIM_DMA_COM ((uint16_t)0x2000) +#define TIM_DMA_Trigger ((uint16_t)0x4000) +#define IS_TIM_DMA_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0x80FF) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Prescaler + * @{ + */ + +#define TIM_ExtTRGPSC_OFF ((uint16_t)0x0000) +#define TIM_ExtTRGPSC_DIV2 ((uint16_t)0x1000) +#define TIM_ExtTRGPSC_DIV4 ((uint16_t)0x2000) +#define TIM_ExtTRGPSC_DIV8 ((uint16_t)0x3000) +#define IS_TIM_EXT_PRESCALER(PRESCALER) (((PRESCALER) == TIM_ExtTRGPSC_OFF) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV2) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV4) || \ + ((PRESCALER) == TIM_ExtTRGPSC_DIV8)) +/** + * @} + */ + +/** @defgroup TIM_Internal_Trigger_Selection + * @{ + */ + +#define TIM_TS_ITR0 ((uint16_t)0x0000) +#define TIM_TS_ITR1 ((uint16_t)0x0010) +#define TIM_TS_ITR2 ((uint16_t)0x0020) +#define TIM_TS_ITR3 ((uint16_t)0x0030) +#define TIM_TS_TI1F_ED ((uint16_t)0x0040) +#define TIM_TS_TI1FP1 ((uint16_t)0x0050) +#define TIM_TS_TI2FP2 ((uint16_t)0x0060) +#define TIM_TS_ETRF ((uint16_t)0x0070) +#define IS_TIM_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3) || \ + ((SELECTION) == TIM_TS_TI1F_ED) || \ + ((SELECTION) == TIM_TS_TI1FP1) || \ + ((SELECTION) == TIM_TS_TI2FP2) || \ + ((SELECTION) == TIM_TS_ETRF)) +#define IS_TIM_INTERNAL_TRIGGER_SELECTION(SELECTION) (((SELECTION) == TIM_TS_ITR0) || \ + ((SELECTION) == TIM_TS_ITR1) || \ + ((SELECTION) == TIM_TS_ITR2) || \ + ((SELECTION) == TIM_TS_ITR3)) +/** + * @} + */ + +/** @defgroup TIM_TIx_External_Clock_Source + * @{ + */ + +#define TIM_TIxExternalCLK1Source_TI1 ((uint16_t)0x0050) +#define TIM_TIxExternalCLK1Source_TI2 ((uint16_t)0x0060) +#define TIM_TIxExternalCLK1Source_TI1ED ((uint16_t)0x0040) +#define IS_TIM_TIXCLK_SOURCE(SOURCE) (((SOURCE) == TIM_TIxExternalCLK1Source_TI1) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI2) || \ + ((SOURCE) == TIM_TIxExternalCLK1Source_TI1ED)) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Polarity + * @{ + */ +#define TIM_ExtTRGPolarity_Inverted ((uint16_t)0x8000) +#define TIM_ExtTRGPolarity_NonInverted ((uint16_t)0x0000) +#define IS_TIM_EXT_POLARITY(POLARITY) (((POLARITY) == TIM_ExtTRGPolarity_Inverted) || \ + ((POLARITY) == TIM_ExtTRGPolarity_NonInverted)) +/** + * @} + */ + +/** @defgroup TIM_Prescaler_Reload_Mode + * @{ + */ + +#define TIM_PSCReloadMode_Update ((uint16_t)0x0000) +#define TIM_PSCReloadMode_Immediate ((uint16_t)0x0001) +#define IS_TIM_PRESCALER_RELOAD(RELOAD) (((RELOAD) == TIM_PSCReloadMode_Update) || \ + ((RELOAD) == TIM_PSCReloadMode_Immediate)) +/** + * @} + */ + +/** @defgroup TIM_Forced_Action + * @{ + */ + +#define TIM_ForcedAction_Active ((uint16_t)0x0050) +#define TIM_ForcedAction_InActive ((uint16_t)0x0040) +#define IS_TIM_FORCED_ACTION(ACTION) (((ACTION) == TIM_ForcedAction_Active) || \ + ((ACTION) == TIM_ForcedAction_InActive)) +/** + * @} + */ + +/** @defgroup TIM_Encoder_Mode + * @{ + */ + +#define TIM_EncoderMode_TI1 ((uint16_t)0x0001) +#define TIM_EncoderMode_TI2 ((uint16_t)0x0002) +#define TIM_EncoderMode_TI12 ((uint16_t)0x0003) +#define IS_TIM_ENCODER_MODE(MODE) (((MODE) == TIM_EncoderMode_TI1) || \ + ((MODE) == TIM_EncoderMode_TI2) || \ + ((MODE) == TIM_EncoderMode_TI12)) +/** + * @} + */ + + +/** @defgroup TIM_Event_Source + * @{ + */ + +#define TIM_EventSource_Update ((uint16_t)0x0001) +#define TIM_EventSource_CC1 ((uint16_t)0x0002) +#define TIM_EventSource_CC2 ((uint16_t)0x0004) +#define TIM_EventSource_CC3 ((uint16_t)0x0008) +#define TIM_EventSource_CC4 ((uint16_t)0x0010) +#define TIM_EventSource_COM ((uint16_t)0x0020) +#define TIM_EventSource_Trigger ((uint16_t)0x0040) +#define TIM_EventSource_Break ((uint16_t)0x0080) +#define IS_TIM_EVENT_SOURCE(SOURCE) ((((SOURCE) & (uint16_t)0xFF00) == 0x0000) && ((SOURCE) != 0x0000)) + +/** + * @} + */ + +/** @defgroup TIM_Update_Source + * @{ + */ + +#define TIM_UpdateSource_Global ((uint16_t)0x0000) /*!< Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. */ +#define TIM_UpdateSource_Regular ((uint16_t)0x0001) /*!< Source of update is counter overflow/underflow. */ +#define IS_TIM_UPDATE_SOURCE(SOURCE) (((SOURCE) == TIM_UpdateSource_Global) || \ + ((SOURCE) == TIM_UpdateSource_Regular)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Preload_State + * @{ + */ + +#define TIM_OCPreload_Enable ((uint16_t)0x0008) +#define TIM_OCPreload_Disable ((uint16_t)0x0000) +#define IS_TIM_OCPRELOAD_STATE(STATE) (((STATE) == TIM_OCPreload_Enable) || \ + ((STATE) == TIM_OCPreload_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Fast_State + * @{ + */ + +#define TIM_OCFast_Enable ((uint16_t)0x0004) +#define TIM_OCFast_Disable ((uint16_t)0x0000) +#define IS_TIM_OCFAST_STATE(STATE) (((STATE) == TIM_OCFast_Enable) || \ + ((STATE) == TIM_OCFast_Disable)) + +/** + * @} + */ + +/** @defgroup TIM_Output_Compare_Clear_State + * @{ + */ + +#define TIM_OCClear_Enable ((uint16_t)0x0080) +#define TIM_OCClear_Disable ((uint16_t)0x0000) +#define IS_TIM_OCCLEAR_STATE(STATE) (((STATE) == TIM_OCClear_Enable) || \ + ((STATE) == TIM_OCClear_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Trigger_Output_Source + * @{ + */ + +#define TIM_TRGOSource_Reset ((uint16_t)0x0000) +#define TIM_TRGOSource_Enable ((uint16_t)0x0010) +#define TIM_TRGOSource_Update ((uint16_t)0x0020) +#define TIM_TRGOSource_OC1 ((uint16_t)0x0030) +#define TIM_TRGOSource_OC1Ref ((uint16_t)0x0040) +#define TIM_TRGOSource_OC2Ref ((uint16_t)0x0050) +#define TIM_TRGOSource_OC3Ref ((uint16_t)0x0060) +#define TIM_TRGOSource_OC4Ref ((uint16_t)0x0070) +#define IS_TIM_TRGO_SOURCE(SOURCE) (((SOURCE) == TIM_TRGOSource_Reset) || \ + ((SOURCE) == TIM_TRGOSource_Enable) || \ + ((SOURCE) == TIM_TRGOSource_Update) || \ + ((SOURCE) == TIM_TRGOSource_OC1) || \ + ((SOURCE) == TIM_TRGOSource_OC1Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC2Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC3Ref) || \ + ((SOURCE) == TIM_TRGOSource_OC4Ref)) +/** + * @} + */ + +/** @defgroup TIM_Slave_Mode + * @{ + */ + +#define TIM_SlaveMode_Reset ((uint16_t)0x0004) +#define TIM_SlaveMode_Gated ((uint16_t)0x0005) +#define TIM_SlaveMode_Trigger ((uint16_t)0x0006) +#define TIM_SlaveMode_External1 ((uint16_t)0x0007) +#define IS_TIM_SLAVE_MODE(MODE) (((MODE) == TIM_SlaveMode_Reset) || \ + ((MODE) == TIM_SlaveMode_Gated) || \ + ((MODE) == TIM_SlaveMode_Trigger) || \ + ((MODE) == TIM_SlaveMode_External1)) +/** + * @} + */ + +/** @defgroup TIM_Master_Slave_Mode + * @{ + */ + +#define TIM_MasterSlaveMode_Enable ((uint16_t)0x0080) +#define TIM_MasterSlaveMode_Disable ((uint16_t)0x0000) +#define IS_TIM_MSM_STATE(STATE) (((STATE) == TIM_MasterSlaveMode_Enable) || \ + ((STATE) == TIM_MasterSlaveMode_Disable)) +/** + * @} + */ + +/** @defgroup TIM_Flags + * @{ + */ + +#define TIM_FLAG_Update ((uint16_t)0x0001) +#define TIM_FLAG_CC1 ((uint16_t)0x0002) +#define TIM_FLAG_CC2 ((uint16_t)0x0004) +#define TIM_FLAG_CC3 ((uint16_t)0x0008) +#define TIM_FLAG_CC4 ((uint16_t)0x0010) +#define TIM_FLAG_COM ((uint16_t)0x0020) +#define TIM_FLAG_Trigger ((uint16_t)0x0040) +#define TIM_FLAG_Break ((uint16_t)0x0080) +#define TIM_FLAG_CC1OF ((uint16_t)0x0200) +#define TIM_FLAG_CC2OF ((uint16_t)0x0400) +#define TIM_FLAG_CC3OF ((uint16_t)0x0800) +#define TIM_FLAG_CC4OF ((uint16_t)0x1000) +#define IS_TIM_GET_FLAG(FLAG) (((FLAG) == TIM_FLAG_Update) || \ + ((FLAG) == TIM_FLAG_CC1) || \ + ((FLAG) == TIM_FLAG_CC2) || \ + ((FLAG) == TIM_FLAG_CC3) || \ + ((FLAG) == TIM_FLAG_CC4) || \ + ((FLAG) == TIM_FLAG_COM) || \ + ((FLAG) == TIM_FLAG_Trigger) || \ + ((FLAG) == TIM_FLAG_Break) || \ + ((FLAG) == TIM_FLAG_CC1OF) || \ + ((FLAG) == TIM_FLAG_CC2OF) || \ + ((FLAG) == TIM_FLAG_CC3OF) || \ + ((FLAG) == TIM_FLAG_CC4OF)) + + +#define IS_TIM_CLEAR_FLAG(TIM_FLAG) ((((TIM_FLAG) & (uint16_t)0xE100) == 0x0000) && ((TIM_FLAG) != 0x0000)) +/** + * @} + */ + +/** @defgroup TIM_Input_Capture_Filer_Value + * @{ + */ + +#define IS_TIM_IC_FILTER(ICFILTER) ((ICFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_External_Trigger_Filter + * @{ + */ + +#define IS_TIM_EXT_FILTER(EXTFILTER) ((EXTFILTER) <= 0xF) +/** + * @} + */ + +/** @defgroup TIM_Legacy + * @{ + */ + +#define TIM_DMABurstLength_1Byte TIM_DMABurstLength_1Transfer +#define TIM_DMABurstLength_2Bytes TIM_DMABurstLength_2Transfers +#define TIM_DMABurstLength_3Bytes TIM_DMABurstLength_3Transfers +#define TIM_DMABurstLength_4Bytes TIM_DMABurstLength_4Transfers +#define TIM_DMABurstLength_5Bytes TIM_DMABurstLength_5Transfers +#define TIM_DMABurstLength_6Bytes TIM_DMABurstLength_6Transfers +#define TIM_DMABurstLength_7Bytes TIM_DMABurstLength_7Transfers +#define TIM_DMABurstLength_8Bytes TIM_DMABurstLength_8Transfers +#define TIM_DMABurstLength_9Bytes TIM_DMABurstLength_9Transfers +#define TIM_DMABurstLength_10Bytes TIM_DMABurstLength_10Transfers +#define TIM_DMABurstLength_11Bytes TIM_DMABurstLength_11Transfers +#define TIM_DMABurstLength_12Bytes TIM_DMABurstLength_12Transfers +#define TIM_DMABurstLength_13Bytes TIM_DMABurstLength_13Transfers +#define TIM_DMABurstLength_14Bytes TIM_DMABurstLength_14Transfers +#define TIM_DMABurstLength_15Bytes TIM_DMABurstLength_15Transfers +#define TIM_DMABurstLength_16Bytes TIM_DMABurstLength_16Transfers +#define TIM_DMABurstLength_17Bytes TIM_DMABurstLength_17Transfers +#define TIM_DMABurstLength_18Bytes TIM_DMABurstLength_18Transfers +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Exported_Functions + * @{ + */ + +void TIM_DeInit(TIM_TypeDef* TIMx); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct); +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState); +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource); +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength); +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState); +void TIM_InternalClockConfig(TIM_TypeDef* TIMx); +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter); +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter); +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter); +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode); +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode); +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource); +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity); +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction); +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload); +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast); +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear); +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity); +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity); +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx); +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN); +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode); +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource); +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState); +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode); +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource); +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode); +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode); +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter); +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload); +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1); +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2); +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3); +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4); +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC); +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD); +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx); +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx); +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx); +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx); +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG); +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT); +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT); + +#ifdef __cplusplus +} +#endif + +#endif /*__STM32F10x_TIM_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h new file mode 100755 index 0000000000..61ae249a47 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_usart.h @@ -0,0 +1,412 @@ +/** + ****************************************************************************** + * @file stm32f10x_usart.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the USART + * firmware library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_USART_H +#define __STM32F10x_USART_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup USART + * @{ + */ + +/** @defgroup USART_Exported_Types + * @{ + */ + +/** + * @brief USART Init Structure definition + */ + +typedef struct +{ + uint32_t USART_BaudRate; /*!< This member configures the USART communication baud rate. + The baud rate is computed using the following formula: + - IntegerDivider = ((PCLKx) / (16 * (USART_InitStruct->USART_BaudRate))) + - FractionalDivider = ((IntegerDivider - ((u32) IntegerDivider)) * 16) + 0.5 */ + + uint16_t USART_WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. + This parameter can be a value of @ref USART_Word_Length */ + + uint16_t USART_StopBits; /*!< Specifies the number of stop bits transmitted. + This parameter can be a value of @ref USART_Stop_Bits */ + + uint16_t USART_Parity; /*!< Specifies the parity mode. + This parameter can be a value of @ref USART_Parity + @note When parity is enabled, the computed parity is inserted + at the MSB position of the transmitted data (9th bit when + the word length is set to 9 data bits; 8th bit when the + word length is set to 8 data bits). */ + + uint16_t USART_Mode; /*!< Specifies wether the Receive or Transmit mode is enabled or disabled. + This parameter can be a value of @ref USART_Mode */ + + uint16_t USART_HardwareFlowControl; /*!< Specifies wether the hardware flow control mode is enabled + or disabled. + This parameter can be a value of @ref USART_Hardware_Flow_Control */ +} USART_InitTypeDef; + +/** + * @brief USART Clock Init Structure definition + */ + +typedef struct +{ + + uint16_t USART_Clock; /*!< Specifies whether the USART clock is enabled or disabled. + This parameter can be a value of @ref USART_Clock */ + + uint16_t USART_CPOL; /*!< Specifies the steady state value of the serial clock. + This parameter can be a value of @ref USART_Clock_Polarity */ + + uint16_t USART_CPHA; /*!< Specifies the clock transition on which the bit capture is made. + This parameter can be a value of @ref USART_Clock_Phase */ + + uint16_t USART_LastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted + data bit (MSB) has to be output on the SCLK pin in synchronous mode. + This parameter can be a value of @ref USART_Last_Bit */ +} USART_ClockInitTypeDef; + +/** + * @} + */ + +/** @defgroup USART_Exported_Constants + * @{ + */ + +#define IS_USART_ALL_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4) || \ + ((PERIPH) == UART5)) + +#define IS_USART_123_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3)) + +#define IS_USART_1234_PERIPH(PERIPH) (((PERIPH) == USART1) || \ + ((PERIPH) == USART2) || \ + ((PERIPH) == USART3) || \ + ((PERIPH) == UART4)) +/** @defgroup USART_Word_Length + * @{ + */ + +#define USART_WordLength_8b ((uint16_t)0x0000) +#define USART_WordLength_9b ((uint16_t)0x1000) + +#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WordLength_8b) || \ + ((LENGTH) == USART_WordLength_9b)) +/** + * @} + */ + +/** @defgroup USART_Stop_Bits + * @{ + */ + +#define USART_StopBits_1 ((uint16_t)0x0000) +#define USART_StopBits_0_5 ((uint16_t)0x1000) +#define USART_StopBits_2 ((uint16_t)0x2000) +#define USART_StopBits_1_5 ((uint16_t)0x3000) +#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_StopBits_1) || \ + ((STOPBITS) == USART_StopBits_0_5) || \ + ((STOPBITS) == USART_StopBits_2) || \ + ((STOPBITS) == USART_StopBits_1_5)) +/** + * @} + */ + +/** @defgroup USART_Parity + * @{ + */ + +#define USART_Parity_No ((uint16_t)0x0000) +#define USART_Parity_Even ((uint16_t)0x0400) +#define USART_Parity_Odd ((uint16_t)0x0600) +#define IS_USART_PARITY(PARITY) (((PARITY) == USART_Parity_No) || \ + ((PARITY) == USART_Parity_Even) || \ + ((PARITY) == USART_Parity_Odd)) +/** + * @} + */ + +/** @defgroup USART_Mode + * @{ + */ + +#define USART_Mode_Rx ((uint16_t)0x0004) +#define USART_Mode_Tx ((uint16_t)0x0008) +#define IS_USART_MODE(MODE) ((((MODE) & (uint16_t)0xFFF3) == 0x00) && ((MODE) != (uint16_t)0x00)) +/** + * @} + */ + +/** @defgroup USART_Hardware_Flow_Control + * @{ + */ +#define USART_HardwareFlowControl_None ((uint16_t)0x0000) +#define USART_HardwareFlowControl_RTS ((uint16_t)0x0100) +#define USART_HardwareFlowControl_CTS ((uint16_t)0x0200) +#define USART_HardwareFlowControl_RTS_CTS ((uint16_t)0x0300) +#define IS_USART_HARDWARE_FLOW_CONTROL(CONTROL)\ + (((CONTROL) == USART_HardwareFlowControl_None) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS) || \ + ((CONTROL) == USART_HardwareFlowControl_CTS) || \ + ((CONTROL) == USART_HardwareFlowControl_RTS_CTS)) +/** + * @} + */ + +/** @defgroup USART_Clock + * @{ + */ +#define USART_Clock_Disable ((uint16_t)0x0000) +#define USART_Clock_Enable ((uint16_t)0x0800) +#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_Clock_Disable) || \ + ((CLOCK) == USART_Clock_Enable)) +/** + * @} + */ + +/** @defgroup USART_Clock_Polarity + * @{ + */ + +#define USART_CPOL_Low ((uint16_t)0x0000) +#define USART_CPOL_High ((uint16_t)0x0400) +#define IS_USART_CPOL(CPOL) (((CPOL) == USART_CPOL_Low) || ((CPOL) == USART_CPOL_High)) + +/** + * @} + */ + +/** @defgroup USART_Clock_Phase + * @{ + */ + +#define USART_CPHA_1Edge ((uint16_t)0x0000) +#define USART_CPHA_2Edge ((uint16_t)0x0200) +#define IS_USART_CPHA(CPHA) (((CPHA) == USART_CPHA_1Edge) || ((CPHA) == USART_CPHA_2Edge)) + +/** + * @} + */ + +/** @defgroup USART_Last_Bit + * @{ + */ + +#define USART_LastBit_Disable ((uint16_t)0x0000) +#define USART_LastBit_Enable ((uint16_t)0x0100) +#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LastBit_Disable) || \ + ((LASTBIT) == USART_LastBit_Enable)) +/** + * @} + */ + +/** @defgroup USART_Interrupt_definition + * @{ + */ + +#define USART_IT_PE ((uint16_t)0x0028) +#define USART_IT_TXE ((uint16_t)0x0727) +#define USART_IT_TC ((uint16_t)0x0626) +#define USART_IT_RXNE ((uint16_t)0x0525) +#define USART_IT_IDLE ((uint16_t)0x0424) +#define USART_IT_LBD ((uint16_t)0x0846) +#define USART_IT_CTS ((uint16_t)0x096A) +#define USART_IT_ERR ((uint16_t)0x0060) +#define USART_IT_ORE ((uint16_t)0x0360) +#define USART_IT_NE ((uint16_t)0x0260) +#define USART_IT_FE ((uint16_t)0x0160) +#define IS_USART_CONFIG_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ERR)) +#define IS_USART_GET_IT(IT) (((IT) == USART_IT_PE) || ((IT) == USART_IT_TXE) || \ + ((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_IDLE) || ((IT) == USART_IT_LBD) || \ + ((IT) == USART_IT_CTS) || ((IT) == USART_IT_ORE) || \ + ((IT) == USART_IT_NE) || ((IT) == USART_IT_FE)) +#define IS_USART_CLEAR_IT(IT) (((IT) == USART_IT_TC) || ((IT) == USART_IT_RXNE) || \ + ((IT) == USART_IT_LBD) || ((IT) == USART_IT_CTS)) +/** + * @} + */ + +/** @defgroup USART_DMA_Requests + * @{ + */ + +#define USART_DMAReq_Tx ((uint16_t)0x0080) +#define USART_DMAReq_Rx ((uint16_t)0x0040) +#define IS_USART_DMAREQ(DMAREQ) ((((DMAREQ) & (uint16_t)0xFF3F) == 0x00) && ((DMAREQ) != (uint16_t)0x00)) + +/** + * @} + */ + +/** @defgroup USART_WakeUp_methods + * @{ + */ + +#define USART_WakeUp_IdleLine ((uint16_t)0x0000) +#define USART_WakeUp_AddressMark ((uint16_t)0x0800) +#define IS_USART_WAKEUP(WAKEUP) (((WAKEUP) == USART_WakeUp_IdleLine) || \ + ((WAKEUP) == USART_WakeUp_AddressMark)) +/** + * @} + */ + +/** @defgroup USART_LIN_Break_Detection_Length + * @{ + */ + +#define USART_LINBreakDetectLength_10b ((uint16_t)0x0000) +#define USART_LINBreakDetectLength_11b ((uint16_t)0x0020) +#define IS_USART_LIN_BREAK_DETECT_LENGTH(LENGTH) \ + (((LENGTH) == USART_LINBreakDetectLength_10b) || \ + ((LENGTH) == USART_LINBreakDetectLength_11b)) +/** + * @} + */ + +/** @defgroup USART_IrDA_Low_Power + * @{ + */ + +#define USART_IrDAMode_LowPower ((uint16_t)0x0004) +#define USART_IrDAMode_Normal ((uint16_t)0x0000) +#define IS_USART_IRDA_MODE(MODE) (((MODE) == USART_IrDAMode_LowPower) || \ + ((MODE) == USART_IrDAMode_Normal)) +/** + * @} + */ + +/** @defgroup USART_Flags + * @{ + */ + +#define USART_FLAG_CTS ((uint16_t)0x0200) +#define USART_FLAG_LBD ((uint16_t)0x0100) +#define USART_FLAG_TXE ((uint16_t)0x0080) +#define USART_FLAG_TC ((uint16_t)0x0040) +#define USART_FLAG_RXNE ((uint16_t)0x0020) +#define USART_FLAG_IDLE ((uint16_t)0x0010) +#define USART_FLAG_ORE ((uint16_t)0x0008) +#define USART_FLAG_NE ((uint16_t)0x0004) +#define USART_FLAG_FE ((uint16_t)0x0002) +#define USART_FLAG_PE ((uint16_t)0x0001) +#define IS_USART_FLAG(FLAG) (((FLAG) == USART_FLAG_PE) || ((FLAG) == USART_FLAG_TXE) || \ + ((FLAG) == USART_FLAG_TC) || ((FLAG) == USART_FLAG_RXNE) || \ + ((FLAG) == USART_FLAG_IDLE) || ((FLAG) == USART_FLAG_LBD) || \ + ((FLAG) == USART_FLAG_CTS) || ((FLAG) == USART_FLAG_ORE) || \ + ((FLAG) == USART_FLAG_NE) || ((FLAG) == USART_FLAG_FE)) + +#define IS_USART_CLEAR_FLAG(FLAG) ((((FLAG) & (uint16_t)0xFC9F) == 0x00) && ((FLAG) != (uint16_t)0x00)) +#define IS_USART_PERIPH_FLAG(PERIPH, USART_FLAG) ((((*(uint32_t*)&(PERIPH)) != UART4_BASE) &&\ + ((*(uint32_t*)&(PERIPH)) != UART5_BASE)) \ + || ((USART_FLAG) != USART_FLAG_CTS)) +#define IS_USART_BAUDRATE(BAUDRATE) (((BAUDRATE) > 0) && ((BAUDRATE) < 0x0044AA21)) +#define IS_USART_ADDRESS(ADDRESS) ((ADDRESS) <= 0xF) +#define IS_USART_DATA(DATA) ((DATA) <= 0x1FF) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Exported_Functions + * @{ + */ + +void USART_DeInit(USART_TypeDef* USARTx); +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct); +void USART_StructInit(USART_InitTypeDef* USART_InitStruct); +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct); +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState); +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState); +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address); +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp); +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength); +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data); +uint16_t USART_ReceiveData(USART_TypeDef* USARTx); +void USART_SendBreak(USART_TypeDef* USARTx); +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime); +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler); +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState); +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode); +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState); +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG); +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG); +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT); +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_USART_H */ +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h new file mode 100755 index 0000000000..cd573da445 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/inc/stm32f10x_wwdg.h @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.h + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file contains all the functions prototypes for the WWDG firmware + * library. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_WWDG_H +#define __STM32F10x_WWDG_H + +#ifdef __cplusplus + extern "C" { +#endif + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @addtogroup WWDG + * @{ + */ + +/** @defgroup WWDG_Exported_Types + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Constants + * @{ + */ + +/** @defgroup WWDG_Prescaler + * @{ + */ + +#define WWDG_Prescaler_1 ((uint32_t)0x00000000) +#define WWDG_Prescaler_2 ((uint32_t)0x00000080) +#define WWDG_Prescaler_4 ((uint32_t)0x00000100) +#define WWDG_Prescaler_8 ((uint32_t)0x00000180) +#define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \ + ((PRESCALER) == WWDG_Prescaler_2) || \ + ((PRESCALER) == WWDG_Prescaler_4) || \ + ((PRESCALER) == WWDG_Prescaler_8)) +#define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F) +#define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F)) + +/** + * @} + */ + +/** + * @} + */ + +/** @defgroup WWDG_Exported_Macros + * @{ + */ +/** + * @} + */ + +/** @defgroup WWDG_Exported_Functions + * @{ + */ + +void WWDG_DeInit(void); +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler); +void WWDG_SetWindowValue(uint8_t WindowValue); +void WWDG_EnableIT(void); +void WWDG_SetCounter(uint8_t Counter); +void WWDG_Enable(uint8_t Counter); +FlagStatus WWDG_GetFlagStatus(void); +void WWDG_ClearFlag(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __STM32F10x_WWDG_H */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/misc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/misc.c new file mode 100755 index 0000000000..ec9165f71f --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/misc.c @@ -0,0 +1,225 @@ +/** + ****************************************************************************** + * @file misc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the miscellaneous firmware functions (add-on + * to CMSIS functions). + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "misc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup MISC + * @brief MISC driver modules + * @{ + */ + +/** @defgroup MISC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Defines + * @{ + */ + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) +/** + * @} + */ + +/** @defgroup MISC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup MISC_Private_Functions + * @{ + */ + +/** + * @brief Configures the priority grouping: pre-emption priority and subpriority. + * @param NVIC_PriorityGroup: specifies the priority grouping bits length. + * This parameter can be one of the following values: + * @arg NVIC_PriorityGroup_0: 0 bits for pre-emption priority + * 4 bits for subpriority + * @arg NVIC_PriorityGroup_1: 1 bits for pre-emption priority + * 3 bits for subpriority + * @arg NVIC_PriorityGroup_2: 2 bits for pre-emption priority + * 2 bits for subpriority + * @arg NVIC_PriorityGroup_3: 3 bits for pre-emption priority + * 1 bits for subpriority + * @arg NVIC_PriorityGroup_4: 4 bits for pre-emption priority + * 0 bits for subpriority + * @retval None + */ +void NVIC_PriorityGroupConfig(uint32_t NVIC_PriorityGroup) +{ + /* Check the parameters */ + assert_param(IS_NVIC_PRIORITY_GROUP(NVIC_PriorityGroup)); + + /* Set the PRIGROUP[10:8] bits according to NVIC_PriorityGroup value */ + SCB->AIRCR = AIRCR_VECTKEY_MASK | NVIC_PriorityGroup; +} + +/** + * @brief Initializes the NVIC peripheral according to the specified + * parameters in the NVIC_InitStruct. + * @param NVIC_InitStruct: pointer to a NVIC_InitTypeDef structure that contains + * the configuration information for the specified NVIC peripheral. + * @retval None + */ +void NVIC_Init(NVIC_InitTypeDef* NVIC_InitStruct) +{ + uint32_t tmppriority = 0x00, tmppre = 0x00, tmpsub = 0x0F; + + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NVIC_InitStruct->NVIC_IRQChannelCmd)); + assert_param(IS_NVIC_PREEMPTION_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority)); + assert_param(IS_NVIC_SUB_PRIORITY(NVIC_InitStruct->NVIC_IRQChannelSubPriority)); + + if (NVIC_InitStruct->NVIC_IRQChannelCmd != DISABLE) + { + /* Compute the Corresponding IRQ Priority --------------------------------*/ + tmppriority = (0x700 - ((SCB->AIRCR) & (uint32_t)0x700))>> 0x08; + tmppre = (0x4 - tmppriority); + tmpsub = tmpsub >> tmppriority; + + tmppriority = (uint32_t)NVIC_InitStruct->NVIC_IRQChannelPreemptionPriority << tmppre; + tmppriority |= NVIC_InitStruct->NVIC_IRQChannelSubPriority & tmpsub; + tmppriority = tmppriority << 0x04; + + NVIC->IP[NVIC_InitStruct->NVIC_IRQChannel] = tmppriority; + + /* Enable the Selected IRQ Channels --------------------------------------*/ + NVIC->ISER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } + else + { + /* Disable the Selected IRQ Channels -------------------------------------*/ + NVIC->ICER[NVIC_InitStruct->NVIC_IRQChannel >> 0x05] = + (uint32_t)0x01 << (NVIC_InitStruct->NVIC_IRQChannel & (uint8_t)0x1F); + } +} + +/** + * @brief Sets the vector table location and Offset. + * @param NVIC_VectTab: specifies if the vector table is in RAM or FLASH memory. + * This parameter can be one of the following values: + * @arg NVIC_VectTab_RAM + * @arg NVIC_VectTab_FLASH + * @param Offset: Vector Table base offset field. This value must be a multiple + * of 0x200. + * @retval None + */ +void NVIC_SetVectorTable(uint32_t NVIC_VectTab, uint32_t Offset) +{ + /* Check the parameters */ + assert_param(IS_NVIC_VECTTAB(NVIC_VectTab)); + assert_param(IS_NVIC_OFFSET(Offset)); + + SCB->VTOR = NVIC_VectTab | (Offset & (uint32_t)0x1FFFFF80); +} + +/** + * @brief Selects the condition for the system to enter low power mode. + * @param LowPowerMode: Specifies the new mode for the system to enter low power mode. + * This parameter can be one of the following values: + * @arg NVIC_LP_SEVONPEND + * @arg NVIC_LP_SLEEPDEEP + * @arg NVIC_LP_SLEEPONEXIT + * @param NewState: new state of LP condition. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void NVIC_SystemLPConfig(uint8_t LowPowerMode, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_NVIC_LP(LowPowerMode)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + SCB->SCR |= LowPowerMode; + } + else + { + SCB->SCR &= (uint32_t)(~(uint32_t)LowPowerMode); + } +} + +/** + * @brief Configures the SysTick clock source. + * @param SysTick_CLKSource: specifies the SysTick clock source. + * This parameter can be one of the following values: + * @arg SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8 selected as SysTick clock source. + * @arg SysTick_CLKSource_HCLK: AHB clock selected as SysTick clock source. + * @retval None + */ +void SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource) +{ + /* Check the parameters */ + assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource)); + if (SysTick_CLKSource == SysTick_CLKSource_HCLK) + { + SysTick->CTRL |= SysTick_CLKSource_HCLK; + } + else + { + SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c new file mode 100755 index 0000000000..916a096d4b --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_adc.c @@ -0,0 +1,1307 @@ +/** + ****************************************************************************** + * @file stm32f10x_adc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the ADC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_adc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup ADC + * @brief ADC driver modules + * @{ + */ + +/** @defgroup ADC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Defines + * @{ + */ + +/* ADC DISCNUM mask */ +#define CR1_DISCNUM_Reset ((uint32_t)0xFFFF1FFF) + +/* ADC DISCEN mask */ +#define CR1_DISCEN_Set ((uint32_t)0x00000800) +#define CR1_DISCEN_Reset ((uint32_t)0xFFFFF7FF) + +/* ADC JAUTO mask */ +#define CR1_JAUTO_Set ((uint32_t)0x00000400) +#define CR1_JAUTO_Reset ((uint32_t)0xFFFFFBFF) + +/* ADC JDISCEN mask */ +#define CR1_JDISCEN_Set ((uint32_t)0x00001000) +#define CR1_JDISCEN_Reset ((uint32_t)0xFFFFEFFF) + +/* ADC AWDCH mask */ +#define CR1_AWDCH_Reset ((uint32_t)0xFFFFFFE0) + +/* ADC Analog watchdog enable mode mask */ +#define CR1_AWDMode_Reset ((uint32_t)0xFF3FFDFF) + +/* CR1 register Mask */ +#define CR1_CLEAR_Mask ((uint32_t)0xFFF0FEFF) + +/* ADC ADON mask */ +#define CR2_ADON_Set ((uint32_t)0x00000001) +#define CR2_ADON_Reset ((uint32_t)0xFFFFFFFE) + +/* ADC DMA mask */ +#define CR2_DMA_Set ((uint32_t)0x00000100) +#define CR2_DMA_Reset ((uint32_t)0xFFFFFEFF) + +/* ADC RSTCAL mask */ +#define CR2_RSTCAL_Set ((uint32_t)0x00000008) + +/* ADC CAL mask */ +#define CR2_CAL_Set ((uint32_t)0x00000004) + +/* ADC SWSTART mask */ +#define CR2_SWSTART_Set ((uint32_t)0x00400000) + +/* ADC EXTTRIG mask */ +#define CR2_EXTTRIG_Set ((uint32_t)0x00100000) +#define CR2_EXTTRIG_Reset ((uint32_t)0xFFEFFFFF) + +/* ADC Software start mask */ +#define CR2_EXTTRIG_SWSTART_Set ((uint32_t)0x00500000) +#define CR2_EXTTRIG_SWSTART_Reset ((uint32_t)0xFFAFFFFF) + +/* ADC JEXTSEL mask */ +#define CR2_JEXTSEL_Reset ((uint32_t)0xFFFF8FFF) + +/* ADC JEXTTRIG mask */ +#define CR2_JEXTTRIG_Set ((uint32_t)0x00008000) +#define CR2_JEXTTRIG_Reset ((uint32_t)0xFFFF7FFF) + +/* ADC JSWSTART mask */ +#define CR2_JSWSTART_Set ((uint32_t)0x00200000) + +/* ADC injected software start mask */ +#define CR2_JEXTTRIG_JSWSTART_Set ((uint32_t)0x00208000) +#define CR2_JEXTTRIG_JSWSTART_Reset ((uint32_t)0xFFDF7FFF) + +/* ADC TSPD mask */ +#define CR2_TSVREFE_Set ((uint32_t)0x00800000) +#define CR2_TSVREFE_Reset ((uint32_t)0xFF7FFFFF) + +/* CR2 register Mask */ +#define CR2_CLEAR_Mask ((uint32_t)0xFFF1F7FD) + +/* ADC SQx mask */ +#define SQR3_SQ_Set ((uint32_t)0x0000001F) +#define SQR2_SQ_Set ((uint32_t)0x0000001F) +#define SQR1_SQ_Set ((uint32_t)0x0000001F) + +/* SQR1 register Mask */ +#define SQR1_CLEAR_Mask ((uint32_t)0xFF0FFFFF) + +/* ADC JSQx mask */ +#define JSQR_JSQ_Set ((uint32_t)0x0000001F) + +/* ADC JL mask */ +#define JSQR_JL_Set ((uint32_t)0x00300000) +#define JSQR_JL_Reset ((uint32_t)0xFFCFFFFF) + +/* ADC SMPx mask */ +#define SMPR1_SMP_Set ((uint32_t)0x00000007) +#define SMPR2_SMP_Set ((uint32_t)0x00000007) + +/* ADC JDRx registers offset */ +#define JDR_Offset ((uint8_t)0x28) + +/* ADC1 DR register base address */ +#define DR_ADDRESS ((uint32_t)0x4001244C) + +/** + * @} + */ + +/** @defgroup ADC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup ADC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the ADCx peripheral registers to their default reset values. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_DeInit(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + + if (ADCx == ADC1) + { + /* Enable ADC1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, ENABLE); + /* Release ADC1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC1, DISABLE); + } + else if (ADCx == ADC2) + { + /* Enable ADC2 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, ENABLE); + /* Release ADC2 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC2, DISABLE); + } + else + { + if (ADCx == ADC3) + { + /* Enable ADC3 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, ENABLE); + /* Release ADC3 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_ADC3, DISABLE); + } + } +} + +/** + * @brief Initializes the ADCx peripheral according to the specified parameters + * in the ADC_InitStruct. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InitStruct: pointer to an ADC_InitTypeDef structure that contains + * the configuration information for the specified ADC peripheral. + * @retval None + */ +void ADC_Init(ADC_TypeDef* ADCx, ADC_InitTypeDef* ADC_InitStruct) +{ + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_MODE(ADC_InitStruct->ADC_Mode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ScanConvMode)); + assert_param(IS_FUNCTIONAL_STATE(ADC_InitStruct->ADC_ContinuousConvMode)); + assert_param(IS_ADC_EXT_TRIG(ADC_InitStruct->ADC_ExternalTrigConv)); + assert_param(IS_ADC_DATA_ALIGN(ADC_InitStruct->ADC_DataAlign)); + assert_param(IS_ADC_REGULAR_LENGTH(ADC_InitStruct->ADC_NbrOfChannel)); + + /*---------------------------- ADCx CR1 Configuration -----------------*/ + /* Get the ADCx CR1 value */ + tmpreg1 = ADCx->CR1; + /* Clear DUALMOD and SCAN bits */ + tmpreg1 &= CR1_CLEAR_Mask; + /* Configure ADCx: Dual mode and scan conversion mode */ + /* Set DUALMOD bits according to ADC_Mode value */ + /* Set SCAN bit according to ADC_ScanConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_Mode | ((uint32_t)ADC_InitStruct->ADC_ScanConvMode << 8)); + /* Write to ADCx CR1 */ + ADCx->CR1 = tmpreg1; + + /*---------------------------- ADCx CR2 Configuration -----------------*/ + /* Get the ADCx CR2 value */ + tmpreg1 = ADCx->CR2; + /* Clear CONT, ALIGN and EXTSEL bits */ + tmpreg1 &= CR2_CLEAR_Mask; + /* Configure ADCx: external trigger event and continuous conversion mode */ + /* Set ALIGN bit according to ADC_DataAlign value */ + /* Set EXTSEL bits according to ADC_ExternalTrigConv value */ + /* Set CONT bit according to ADC_ContinuousConvMode value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->ADC_DataAlign | ADC_InitStruct->ADC_ExternalTrigConv | + ((uint32_t)ADC_InitStruct->ADC_ContinuousConvMode << 1)); + /* Write to ADCx CR2 */ + ADCx->CR2 = tmpreg1; + + /*---------------------------- ADCx SQR1 Configuration -----------------*/ + /* Get the ADCx SQR1 value */ + tmpreg1 = ADCx->SQR1; + /* Clear L bits */ + tmpreg1 &= SQR1_CLEAR_Mask; + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ADC_NbrOfChannel value */ + tmpreg2 |= (uint8_t) (ADC_InitStruct->ADC_NbrOfChannel - (uint8_t)1); + tmpreg1 |= (uint32_t)tmpreg2 << 20; + /* Write to ADCx SQR1 */ + ADCx->SQR1 = tmpreg1; +} + +/** + * @brief Fills each ADC_InitStruct member with its default value. + * @param ADC_InitStruct : pointer to an ADC_InitTypeDef structure which will be initialized. + * @retval None + */ +void ADC_StructInit(ADC_InitTypeDef* ADC_InitStruct) +{ + /* Reset ADC init structure parameters values */ + /* Initialize the ADC_Mode member */ + ADC_InitStruct->ADC_Mode = ADC_Mode_Independent; + /* initialize the ADC_ScanConvMode member */ + ADC_InitStruct->ADC_ScanConvMode = DISABLE; + /* Initialize the ADC_ContinuousConvMode member */ + ADC_InitStruct->ADC_ContinuousConvMode = DISABLE; + /* Initialize the ADC_ExternalTrigConv member */ + ADC_InitStruct->ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1; + /* Initialize the ADC_DataAlign member */ + ADC_InitStruct->ADC_DataAlign = ADC_DataAlign_Right; + /* Initialize the ADC_NbrOfChannel member */ + ADC_InitStruct->ADC_NbrOfChannel = 1; +} + +/** + * @brief Enables or disables the specified ADC peripheral. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the ADCx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_Cmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ADON bit to wake up the ADC from power down mode */ + ADCx->CR2 |= CR2_ADON_Set; + } + else + { + /* Disable the selected ADC peripheral */ + ADCx->CR2 &= CR2_ADON_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC DMA request. + * @param ADCx: where x can be 1 or 3 to select the ADC peripheral. + * Note: ADC2 hasn't a DMA capability. + * @param NewState: new state of the selected ADC DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DMACmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_DMA_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC DMA request */ + ADCx->CR2 |= CR2_DMA_Set; + } + else + { + /* Disable the selected ADC DMA request */ + ADCx->CR2 &= CR2_DMA_Reset; + } +} + +/** + * @brief Enables or disables the specified ADC interrupts. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @param NewState: new state of the specified ADC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ITConfig(ADC_TypeDef* ADCx, uint16_t ADC_IT, FunctionalState NewState) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + if (NewState != DISABLE) + { + /* Enable the selected ADC interrupts */ + ADCx->CR1 |= itmask; + } + else + { + /* Disable the selected ADC interrupts */ + ADCx->CR1 &= (~(uint32_t)itmask); + } +} + +/** + * @brief Resets the selected ADC calibration registers. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_ResetCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Resets the selected ADC calibration registers */ + ADCx->CR2 |= CR2_RSTCAL_Set; +} + +/** + * @brief Gets the selected ADC reset calibration registers status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC reset calibration registers (SET or RESET). + */ +FlagStatus ADC_GetResetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of RSTCAL bit */ + if ((ADCx->CR2 & CR2_RSTCAL_Set) != (uint32_t)RESET) + { + /* RSTCAL bit is set */ + bitstatus = SET; + } + else + { + /* RSTCAL bit is reset */ + bitstatus = RESET; + } + /* Return the RSTCAL bit status */ + return bitstatus; +} + +/** + * @brief Starts the selected ADC calibration process. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval None + */ +void ADC_StartCalibration(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Enable the selected ADC calibration process */ + ADCx->CR2 |= CR2_CAL_Set; +} + +/** + * @brief Gets the selected ADC calibration status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC calibration (SET or RESET). + */ +FlagStatus ADC_GetCalibrationStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of CAL bit */ + if ((ADCx->CR2 & CR2_CAL_Set) != (uint32_t)RESET) + { + /* CAL bit is set: calibration on going */ + bitstatus = SET; + } + else + { + /* CAL bit is reset: end of calibration */ + bitstatus = RESET; + } + /* Return the CAL bit status */ + return bitstatus; +} + +/** + * @brief Enables or disables the selected ADC software start conversion . + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event and start the selected + ADC conversion */ + ADCx->CR2 |= CR2_EXTTRIG_SWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event and stop the selected + ADC conversion */ + ADCx->CR2 &= CR2_EXTTRIG_SWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartConvStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of SWSTART bit */ + if ((ADCx->CR2 & CR2_SWSTART_Set) != (uint32_t)RESET) + { + /* SWSTART bit is set */ + bitstatus = SET; + } + else + { + /* SWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the SWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures the discontinuous mode for the selected ADC regular + * group channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Number: specifies the discontinuous mode regular channel + * count value. This number must be between 1 and 8. + * @retval None + */ +void ADC_DiscModeChannelCountConfig(ADC_TypeDef* ADCx, uint8_t Number) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_REGULAR_DISC_NUMBER(Number)); + /* Get the old register value */ + tmpreg1 = ADCx->CR1; + /* Clear the old discontinuous mode channel count */ + tmpreg1 &= CR1_DISCNUM_Reset; + /* Set the discontinuous mode channel count */ + tmpreg2 = Number - 1; + tmpreg1 |= tmpreg2 << 13; + /* Store the new register value */ + ADCx->CR1 = tmpreg1; +} + +/** + * @brief Enables or disables the discontinuous mode on regular group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on regular group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_DiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC regular discontinuous mode */ + ADCx->CR1 |= CR1_DISCEN_Set; + } + else + { + /* Disable the selected ADC regular discontinuous mode */ + ADCx->CR1 &= CR1_DISCEN_Reset; + } +} + +/** + * @brief Configures for the selected ADC regular channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the regular group sequencer. This parameter must be between 1 to 16. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_RegularChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_REGULAR_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR3; + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SQ_Set << (5 * (Rank - 1)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR2; + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SQ_Set << (5 * (Rank - 7)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else + { + /* Get the old register value */ + tmpreg1 = ADCx->SQR1; + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SQ_Set << (5 * (Rank - 13)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SQR1 = tmpreg1; + } +} + +/** + * @brief Enables or disables the ADCx conversion through external trigger. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion on external event */ + ADCx->CR2 |= CR2_EXTTRIG_Set; + } + else + { + /* Disable the selected ADC conversion on external event */ + ADCx->CR2 &= CR2_EXTTRIG_Reset; + } +} + +/** + * @brief Returns the last ADCx conversion result data for regular channel. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The Data conversion value. + */ +uint16_t ADC_GetConversionValue(ADC_TypeDef* ADCx) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Return the selected ADC conversion value */ + return (uint16_t) ADCx->DR; +} + +/** + * @brief Returns the last ADC1 and ADC2 conversion result data in dual mode. + * @retval The Data conversion value. + */ +uint32_t ADC_GetDualModeConversionValue(void) +{ + /* Return the dual mode conversion value */ + return (*(__IO uint32_t *) DR_ADDRESS); +} + +/** + * @brief Enables or disables the selected ADC automatic injected group + * conversion after regular one. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC auto injected conversion + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_AutoInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC automatic injected group conversion */ + ADCx->CR1 |= CR1_JAUTO_Set; + } + else + { + /* Disable the selected ADC automatic injected group conversion */ + ADCx->CR1 &= CR1_JAUTO_Reset; + } +} + +/** + * @brief Enables or disables the discontinuous mode for injected group + * channel for the specified ADC + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC discontinuous mode + * on injected group channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_InjectedDiscModeCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC injected discontinuous mode */ + ADCx->CR1 |= CR1_JDISCEN_Set; + } + else + { + /* Disable the selected ADC injected discontinuous mode */ + ADCx->CR1 &= CR1_JDISCEN_Reset; + } +} + +/** + * @brief Configures the ADCx external trigger for injected channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_ExternalTrigInjecConv: specifies the ADC trigger to start injected conversion. + * This parameter can be one of the following values: + * @arg ADC_ExternalTrigInjecConv_T1_TRGO: Timer1 TRGO event selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T1_CC4: Timer1 capture compare4 selected (for ADC1, ADC2 and ADC3) + * @arg ADC_ExternalTrigInjecConv_T2_TRGO: Timer2 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T2_CC1: Timer2 capture compare1 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T3_CC4: Timer3 capture compare4 selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_TRGO: Timer4 TRGO event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_Ext_IT15_TIM8_CC4: External interrupt line 15 or Timer8 + * capture compare4 event selected (for ADC1 and ADC2) + * @arg ADC_ExternalTrigInjecConv_T4_CC3: Timer4 capture compare3 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC2: Timer8 capture compare2 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T8_CC4: Timer8 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_TRGO: Timer5 TRGO event selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_T5_CC4: Timer5 capture compare4 selected (for ADC3 only) + * @arg ADC_ExternalTrigInjecConv_None: Injected conversion started by software and not + * by external trigger (for ADC1, ADC2 and ADC3) + * @retval None + */ +void ADC_ExternalTrigInjectedConvConfig(ADC_TypeDef* ADCx, uint32_t ADC_ExternalTrigInjecConv) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_EXT_INJEC_TRIG(ADC_ExternalTrigInjecConv)); + /* Get the old register value */ + tmpreg = ADCx->CR2; + /* Clear the old external event selection for injected group */ + tmpreg &= CR2_JEXTSEL_Reset; + /* Set the external event selection for injected group */ + tmpreg |= ADC_ExternalTrigInjecConv; + /* Store the new register value */ + ADCx->CR2 = tmpreg; +} + +/** + * @brief Enables or disables the ADCx injected channels conversion through + * external trigger + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC external trigger start of + * injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_ExternalTrigInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC external event selection for injected group */ + ADCx->CR2 |= CR2_JEXTTRIG_Set; + } + else + { + /* Disable the selected ADC external event selection for injected group */ + ADCx->CR2 &= CR2_JEXTTRIG_Reset; + } +} + +/** + * @brief Enables or disables the selected ADC start of the injected + * channels conversion. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param NewState: new state of the selected ADC software start injected conversion. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_SoftwareStartInjectedConvCmd(ADC_TypeDef* ADCx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected ADC conversion for injected group on external event and start the selected + ADC injected conversion */ + ADCx->CR2 |= CR2_JEXTTRIG_JSWSTART_Set; + } + else + { + /* Disable the selected ADC conversion on external event for injected group and stop the selected + ADC injected conversion */ + ADCx->CR2 &= CR2_JEXTTRIG_JSWSTART_Reset; + } +} + +/** + * @brief Gets the selected ADC Software start injected conversion Status. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @retval The new state of ADC software start injected conversion (SET or RESET). + */ +FlagStatus ADC_GetSoftwareStartInjectedConvCmdStatus(ADC_TypeDef* ADCx) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + /* Check the status of JSWSTART bit */ + if ((ADCx->CR2 & CR2_JSWSTART_Set) != (uint32_t)RESET) + { + /* JSWSTART bit is set */ + bitstatus = SET; + } + else + { + /* JSWSTART bit is reset */ + bitstatus = RESET; + } + /* Return the JSWSTART bit status */ + return bitstatus; +} + +/** + * @brief Configures for the selected ADC injected channel its corresponding + * rank in the sequencer and its sample time. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @param Rank: The rank in the injected group sequencer. This parameter must be between 1 and 4. + * @param ADC_SampleTime: The sample time value to be set for the selected channel. + * This parameter can be one of the following values: + * @arg ADC_SampleTime_1Cycles5: Sample time equal to 1.5 cycles + * @arg ADC_SampleTime_7Cycles5: Sample time equal to 7.5 cycles + * @arg ADC_SampleTime_13Cycles5: Sample time equal to 13.5 cycles + * @arg ADC_SampleTime_28Cycles5: Sample time equal to 28.5 cycles + * @arg ADC_SampleTime_41Cycles5: Sample time equal to 41.5 cycles + * @arg ADC_SampleTime_55Cycles5: Sample time equal to 55.5 cycles + * @arg ADC_SampleTime_71Cycles5: Sample time equal to 71.5 cycles + * @arg ADC_SampleTime_239Cycles5: Sample time equal to 239.5 cycles + * @retval None + */ +void ADC_InjectedChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0, tmpreg3 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + assert_param(IS_ADC_INJECTED_RANK(Rank)); + assert_param(IS_ADC_SAMPLE_TIME(ADC_SampleTime)); + /* if ADC_Channel_10 ... ADC_Channel_17 is selected */ + if (ADC_Channel > ADC_Channel_9) + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR1; + /* Calculate the mask to clear */ + tmpreg2 = SMPR1_SMP_Set << (3*(ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3*(ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR1 = tmpreg1; + } + else /* ADC_Channel include in ADC_Channel_[0..9] */ + { + /* Get the old register value */ + tmpreg1 = ADCx->SMPR2; + /* Calculate the mask to clear */ + tmpreg2 = SMPR2_SMP_Set << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->SMPR2 = tmpreg1; + } + /* Rank configuration */ + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Get JL value: Number = JL+1 */ + tmpreg3 = (tmpreg1 & JSQR_JL_Set)>> 20; + /* Calculate the mask to clear: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = JSQR_JSQ_Set << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Clear the old JSQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set: ((Rank-1)+(4-JL-1)) */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (uint8_t)((Rank + 3) - (tmpreg3 + 1))); + /* Set the JSQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Configures the sequencer length for injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param Length: The sequencer length. + * This parameter must be a number between 1 to 4. + * @retval None + */ +void ADC_InjectedSequencerLengthConfig(ADC_TypeDef* ADCx, uint8_t Length) +{ + uint32_t tmpreg1 = 0; + uint32_t tmpreg2 = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_LENGTH(Length)); + + /* Get the old register value */ + tmpreg1 = ADCx->JSQR; + /* Clear the old injected sequnence lenght JL bits */ + tmpreg1 &= JSQR_JL_Reset; + /* Set the injected sequnence lenght JL bits */ + tmpreg2 = Length - 1; + tmpreg1 |= tmpreg2 << 20; + /* Store the new register value */ + ADCx->JSQR = tmpreg1; +} + +/** + * @brief Set the injected channels conversion value offset + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the ADC injected channel to set its offset. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @param Offset: the offset value for the selected ADC injected channel + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_SetInjectedOffset(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel, uint16_t Offset) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + assert_param(IS_ADC_OFFSET(Offset)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel; + + /* Set the selected injected channel data offset */ + *(__IO uint32_t *) tmp = (uint32_t)Offset; +} + +/** + * @brief Returns the ADC injected channel conversion result + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_InjectedChannel: the converted ADC injected channel. + * This parameter can be one of the following values: + * @arg ADC_InjectedChannel_1: Injected Channel1 selected + * @arg ADC_InjectedChannel_2: Injected Channel2 selected + * @arg ADC_InjectedChannel_3: Injected Channel3 selected + * @arg ADC_InjectedChannel_4: Injected Channel4 selected + * @retval The Data conversion value. + */ +uint16_t ADC_GetInjectedConversionValue(ADC_TypeDef* ADCx, uint8_t ADC_InjectedChannel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_INJECTED_CHANNEL(ADC_InjectedChannel)); + + tmp = (uint32_t)ADCx; + tmp += ADC_InjectedChannel + JDR_Offset; + + /* Returns the selected injected channel conversion data value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +/** + * @brief Enables or disables the analog watchdog on single/all regular + * or injected channels + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_AnalogWatchdog: the ADC analog watchdog configuration. + * This parameter can be one of the following values: + * @arg ADC_AnalogWatchdog_SingleRegEnable: Analog watchdog on a single regular channel + * @arg ADC_AnalogWatchdog_SingleInjecEnable: Analog watchdog on a single injected channel + * @arg ADC_AnalogWatchdog_SingleRegOrInjecEnable: Analog watchdog on a single regular or injected channel + * @arg ADC_AnalogWatchdog_AllRegEnable: Analog watchdog on all regular channel + * @arg ADC_AnalogWatchdog_AllInjecEnable: Analog watchdog on all injected channel + * @arg ADC_AnalogWatchdog_AllRegAllInjecEnable: Analog watchdog on all regular and injected channels + * @arg ADC_AnalogWatchdog_None: No channel guarded by the analog watchdog + * @retval None + */ +void ADC_AnalogWatchdogCmd(ADC_TypeDef* ADCx, uint32_t ADC_AnalogWatchdog) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_ANALOG_WATCHDOG(ADC_AnalogWatchdog)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear AWDEN, AWDENJ and AWDSGL bits */ + tmpreg &= CR1_AWDMode_Reset; + /* Set the analog watchdog enable mode */ + tmpreg |= ADC_AnalogWatchdog; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Configures the high and low thresholds of the analog watchdog. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param HighThreshold: the ADC analog watchdog High threshold value. + * This parameter must be a 12bit value. + * @param LowThreshold: the ADC analog watchdog Low threshold value. + * This parameter must be a 12bit value. + * @retval None + */ +void ADC_AnalogWatchdogThresholdsConfig(ADC_TypeDef* ADCx, uint16_t HighThreshold, + uint16_t LowThreshold) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_THRESHOLD(HighThreshold)); + assert_param(IS_ADC_THRESHOLD(LowThreshold)); + /* Set the ADCx high threshold */ + ADCx->HTR = HighThreshold; + /* Set the ADCx low threshold */ + ADCx->LTR = LowThreshold; +} + +/** + * @brief Configures the analog watchdog guarded single channel + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_Channel: the ADC channel to configure for the analog watchdog. + * This parameter can be one of the following values: + * @arg ADC_Channel_0: ADC Channel0 selected + * @arg ADC_Channel_1: ADC Channel1 selected + * @arg ADC_Channel_2: ADC Channel2 selected + * @arg ADC_Channel_3: ADC Channel3 selected + * @arg ADC_Channel_4: ADC Channel4 selected + * @arg ADC_Channel_5: ADC Channel5 selected + * @arg ADC_Channel_6: ADC Channel6 selected + * @arg ADC_Channel_7: ADC Channel7 selected + * @arg ADC_Channel_8: ADC Channel8 selected + * @arg ADC_Channel_9: ADC Channel9 selected + * @arg ADC_Channel_10: ADC Channel10 selected + * @arg ADC_Channel_11: ADC Channel11 selected + * @arg ADC_Channel_12: ADC Channel12 selected + * @arg ADC_Channel_13: ADC Channel13 selected + * @arg ADC_Channel_14: ADC Channel14 selected + * @arg ADC_Channel_15: ADC Channel15 selected + * @arg ADC_Channel_16: ADC Channel16 selected + * @arg ADC_Channel_17: ADC Channel17 selected + * @retval None + */ +void ADC_AnalogWatchdogSingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Channel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CHANNEL(ADC_Channel)); + /* Get the old register value */ + tmpreg = ADCx->CR1; + /* Clear the Analog watchdog channel select bits */ + tmpreg &= CR1_AWDCH_Reset; + /* Set the Analog watchdog channel */ + tmpreg |= ADC_Channel; + /* Store the new register value */ + ADCx->CR1 = tmpreg; +} + +/** + * @brief Enables or disables the temperature sensor and Vrefint channel. + * @param NewState: new state of the temperature sensor. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void ADC_TempSensorVrefintCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the temperature sensor and Vrefint channel*/ + ADC1->CR2 |= CR2_TSVREFE_Set; + } + else + { + /* Disable the temperature sensor and Vrefint channel*/ + ADC1->CR2 &= CR2_TSVREFE_Reset; + } +} + +/** + * @brief Checks whether the specified ADC flag is set or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval The new state of ADC_FLAG (SET or RESET). + */ +FlagStatus ADC_GetFlagStatus(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_FLAG(ADC_FLAG)); + /* Check the status of the specified ADC flag */ + if ((ADCx->SR & ADC_FLAG) != (uint8_t)RESET) + { + /* ADC_FLAG is set */ + bitstatus = SET; + } + else + { + /* ADC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's pending flags. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg ADC_FLAG_AWD: Analog watchdog flag + * @arg ADC_FLAG_EOC: End of conversion flag + * @arg ADC_FLAG_JEOC: End of injected group conversion flag + * @arg ADC_FLAG_JSTRT: Start of injected group conversion flag + * @arg ADC_FLAG_STRT: Start of regular group conversion flag + * @retval None + */ +void ADC_ClearFlag(ADC_TypeDef* ADCx, uint8_t ADC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_CLEAR_FLAG(ADC_FLAG)); + /* Clear the selected ADC flags */ + ADCx->SR = ~(uint32_t)ADC_FLAG; +} + +/** + * @brief Checks whether the specified ADC interrupt has occurred or not. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt source to check. + * This parameter can be one of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval The new state of ADC_IT (SET or RESET). + */ +ITStatus ADC_GetITStatus(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t itmask = 0, enablestatus = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_GET_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = ADC_IT >> 8; + /* Get the ADC_IT enable bit status */ + enablestatus = (ADCx->CR1 & (uint8_t)ADC_IT) ; + /* Check the status of the specified ADC interrupt */ + if (((ADCx->SR & itmask) != (uint32_t)RESET) && enablestatus) + { + /* ADC_IT is set */ + bitstatus = SET; + } + else + { + /* ADC_IT is reset */ + bitstatus = RESET; + } + /* Return the ADC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the ADCx's interrupt pending bits. + * @param ADCx: where x can be 1, 2 or 3 to select the ADC peripheral. + * @param ADC_IT: specifies the ADC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg ADC_IT_EOC: End of conversion interrupt mask + * @arg ADC_IT_AWD: Analog watchdog interrupt mask + * @arg ADC_IT_JEOC: End of injected conversion interrupt mask + * @retval None + */ +void ADC_ClearITPendingBit(ADC_TypeDef* ADCx, uint16_t ADC_IT) +{ + uint8_t itmask = 0; + /* Check the parameters */ + assert_param(IS_ADC_ALL_PERIPH(ADCx)); + assert_param(IS_ADC_IT(ADC_IT)); + /* Get the ADC IT index */ + itmask = (uint8_t)(ADC_IT >> 8); + /* Clear the selected ADC interrupt pending bits */ + ADCx->SR = ~(uint32_t)itmask; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c new file mode 100755 index 0000000000..3004b9ef80 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_bkp.c @@ -0,0 +1,308 @@ +/** + ****************************************************************************** + * @file stm32f10x_bkp.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the BKP firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_bkp.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup BKP + * @brief BKP driver modules + * @{ + */ + +/** @defgroup BKP_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Defines + * @{ + */ + +/* ------------ BKP registers bit address in the alias region --------------- */ +#define BKP_OFFSET (BKP_BASE - PERIPH_BASE) + +/* --- CR Register ----*/ + +/* Alias word address of TPAL bit */ +#define CR_OFFSET (BKP_OFFSET + 0x30) +#define TPAL_BitNumber 0x01 +#define CR_TPAL_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPAL_BitNumber * 4)) + +/* Alias word address of TPE bit */ +#define TPE_BitNumber 0x00 +#define CR_TPE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (TPE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TPIE bit */ +#define CSR_OFFSET (BKP_OFFSET + 0x34) +#define TPIE_BitNumber 0x02 +#define CSR_TPIE_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TPIE_BitNumber * 4)) + +/* Alias word address of TIF bit */ +#define TIF_BitNumber 0x09 +#define CSR_TIF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TIF_BitNumber * 4)) + +/* Alias word address of TEF bit */ +#define TEF_BitNumber 0x08 +#define CSR_TEF_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEF_BitNumber * 4)) + +/* ---------------------- BKP registers bit mask ------------------------ */ + +/* RTCCR register bit mask */ +#define RTCCR_CAL_MASK ((uint16_t)0xFF80) +#define RTCCR_MASK ((uint16_t)0xFC7F) + +/** + * @} + */ + + +/** @defgroup BKP_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup BKP_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the BKP peripheral registers to their default reset values. + * @param None + * @retval None + */ +void BKP_DeInit(void) +{ + RCC_BackupResetCmd(ENABLE); + RCC_BackupResetCmd(DISABLE); +} + +/** + * @brief Configures the Tamper Pin active level. + * @param BKP_TamperPinLevel: specifies the Tamper Pin active level. + * This parameter can be one of the following values: + * @arg BKP_TamperPinLevel_High: Tamper pin active on high level + * @arg BKP_TamperPinLevel_Low: Tamper pin active on low level + * @retval None + */ +void BKP_TamperPinLevelConfig(uint16_t BKP_TamperPinLevel) +{ + /* Check the parameters */ + assert_param(IS_BKP_TAMPER_PIN_LEVEL(BKP_TamperPinLevel)); + *(__IO uint32_t *) CR_TPAL_BB = BKP_TamperPinLevel; +} + +/** + * @brief Enables or disables the Tamper Pin activation. + * @param NewState: new state of the Tamper Pin activation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_TamperPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_TPE_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Tamper Pin Interrupt. + * @param NewState: new state of the Tamper Pin Interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void BKP_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_TPIE_BB = (uint32_t)NewState; +} + +/** + * @brief Select the RTC output source to output on the Tamper pin. + * @param BKP_RTCOutputSource: specifies the RTC output source. + * This parameter can be one of the following values: + * @arg BKP_RTCOutputSource_None: no RTC output on the Tamper pin. + * @arg BKP_RTCOutputSource_CalibClock: output the RTC clock with frequency + * divided by 64 on the Tamper pin. + * @arg BKP_RTCOutputSource_Alarm: output the RTC Alarm pulse signal on + * the Tamper pin. + * @arg BKP_RTCOutputSource_Second: output the RTC Second pulse signal on + * the Tamper pin. + * @retval None + */ +void BKP_RTCOutputConfig(uint16_t BKP_RTCOutputSource) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_RTC_OUTPUT_SOURCE(BKP_RTCOutputSource)); + tmpreg = BKP->RTCCR; + /* Clear CCO, ASOE and ASOS bits */ + tmpreg &= RTCCR_MASK; + + /* Set CCO, ASOE and ASOS bits according to BKP_RTCOutputSource value */ + tmpreg |= BKP_RTCOutputSource; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Sets RTC Clock Calibration value. + * @param CalibrationValue: specifies the RTC Clock Calibration value. + * This parameter must be a number between 0 and 0x7F. + * @retval None + */ +void BKP_SetRTCCalibrationValue(uint8_t CalibrationValue) +{ + uint16_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_BKP_CALIBRATION_VALUE(CalibrationValue)); + tmpreg = BKP->RTCCR; + /* Clear CAL[6:0] bits */ + tmpreg &= RTCCR_CAL_MASK; + /* Set CAL[6:0] bits according to CalibrationValue value */ + tmpreg |= CalibrationValue; + /* Store the new value */ + BKP->RTCCR = tmpreg; +} + +/** + * @brief Writes user data to the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @param Data: data to write + * @retval None + */ +void BKP_WriteBackupRegister(uint16_t BKP_DR, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Reads data from the specified Data Backup Register. + * @param BKP_DR: specifies the Data Backup Register. + * This parameter can be BKP_DRx where x:[1, 42] + * @retval The content of the specified Data Backup Register + */ +uint16_t BKP_ReadBackupRegister(uint16_t BKP_DR) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_BKP_DR(BKP_DR)); + + tmp = (uint32_t)BKP_BASE; + tmp += BKP_DR; + + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Checks whether the Tamper Pin Event flag is set or not. + * @param None + * @retval The new state of the Tamper Pin Event flag (SET or RESET). + */ +FlagStatus BKP_GetFlagStatus(void) +{ + return (FlagStatus)(*(__IO uint32_t *) CSR_TEF_BB); +} + +/** + * @brief Clears Tamper Pin Event pending flag. + * @param None + * @retval None + */ +void BKP_ClearFlag(void) +{ + /* Set CTE bit to clear Tamper Pin Event flag */ + BKP->CSR |= BKP_CSR_CTE; +} + +/** + * @brief Checks whether the Tamper Pin Interrupt has occurred or not. + * @param None + * @retval The new state of the Tamper Pin Interrupt (SET or RESET). + */ +ITStatus BKP_GetITStatus(void) +{ + return (ITStatus)(*(__IO uint32_t *) CSR_TIF_BB); +} + +/** + * @brief Clears Tamper Pin Interrupt pending bit. + * @param None + * @retval None + */ +void BKP_ClearITPendingBit(void) +{ + /* Set CTI bit to clear Tamper Pin Interrupt pending bit */ + BKP->CSR |= BKP_CSR_CTI; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c new file mode 100755 index 0000000000..607d6924f7 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_can.c @@ -0,0 +1,1415 @@ +/** + ****************************************************************************** + * @file stm32f10x_can.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CAN firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_can.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CAN + * @brief CAN driver modules + * @{ + */ + +/** @defgroup CAN_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Defines + * @{ + */ + +/* CAN Master Control Register bits */ + +#define MCR_DBF ((uint32_t)0x00010000) /* software master reset */ + +/* CAN Mailbox Transmit Request */ +#define TMIDxR_TXRQ ((uint32_t)0x00000001) /* Transmit mailbox request */ + +/* CAN Filter Master Register bits */ +#define FMR_FINIT ((uint32_t)0x00000001) /* Filter init mode */ + +/* Time out for INAK bit */ +#define INAK_TIMEOUT ((uint32_t)0x0000FFFF) +/* Time out for SLAK bit */ +#define SLAK_TIMEOUT ((uint32_t)0x0000FFFF) + + + +/* Flags in TSR register */ +#define CAN_FLAGS_TSR ((uint32_t)0x08000000) +/* Flags in RF1R register */ +#define CAN_FLAGS_RF1R ((uint32_t)0x04000000) +/* Flags in RF0R register */ +#define CAN_FLAGS_RF0R ((uint32_t)0x02000000) +/* Flags in MSR register */ +#define CAN_FLAGS_MSR ((uint32_t)0x01000000) +/* Flags in ESR register */ +#define CAN_FLAGS_ESR ((uint32_t)0x00F00000) + +/* Mailboxes definition */ +#define CAN_TXMAILBOX_0 ((uint8_t)0x00) +#define CAN_TXMAILBOX_1 ((uint8_t)0x01) +#define CAN_TXMAILBOX_2 ((uint8_t)0x02) + + + +#define CAN_MODE_MASK ((uint32_t) 0x00000003) +/** + * @} + */ + +/** @defgroup CAN_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CAN_Private_FunctionPrototypes + * @{ + */ + +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit); + +/** + * @} + */ + +/** @defgroup CAN_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CAN peripheral registers to their default reset values. + * @param CANx: where x can be 1 or 2 to select the CAN peripheral. + * @retval None. + */ +void CAN_DeInit(CAN_TypeDef* CANx) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + if (CANx == CAN1) + { + /* Enable CAN1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, ENABLE); + /* Release CAN1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN1, DISABLE); + } + else + { + /* Enable CAN2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, ENABLE); + /* Release CAN2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CAN2, DISABLE); + } +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_InitStruct. + * @param CANx: where x can be 1 or 2 to to select the CAN + * peripheral. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure that + * contains the configuration information for the + * CAN peripheral. + * @retval Constant indicates initialization succeed which will be + * CAN_InitStatus_Failed or CAN_InitStatus_Success. + */ +uint8_t CAN_Init(CAN_TypeDef* CANx, CAN_InitTypeDef* CAN_InitStruct) +{ + uint8_t InitStatus = CAN_InitStatus_Failed; + uint32_t wait_ack = 0x00000000; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TTCM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_ABOM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_AWUM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_NART)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_RFLM)); + assert_param(IS_FUNCTIONAL_STATE(CAN_InitStruct->CAN_TXFP)); + assert_param(IS_CAN_MODE(CAN_InitStruct->CAN_Mode)); + assert_param(IS_CAN_SJW(CAN_InitStruct->CAN_SJW)); + assert_param(IS_CAN_BS1(CAN_InitStruct->CAN_BS1)); + assert_param(IS_CAN_BS2(CAN_InitStruct->CAN_BS2)); + assert_param(IS_CAN_PRESCALER(CAN_InitStruct->CAN_Prescaler)); + + /* Exit from sleep mode */ + CANx->MCR &= (~(uint32_t)CAN_MCR_SLEEP); + + /* Request initialisation */ + CANx->MCR |= CAN_MCR_INRQ ; + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* Check acknowledge */ + if ((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + /* Set the time triggered communication mode */ + if (CAN_InitStruct->CAN_TTCM == ENABLE) + { + CANx->MCR |= CAN_MCR_TTCM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TTCM; + } + + /* Set the automatic bus-off management */ + if (CAN_InitStruct->CAN_ABOM == ENABLE) + { + CANx->MCR |= CAN_MCR_ABOM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_ABOM; + } + + /* Set the automatic wake-up mode */ + if (CAN_InitStruct->CAN_AWUM == ENABLE) + { + CANx->MCR |= CAN_MCR_AWUM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_AWUM; + } + + /* Set the no automatic retransmission */ + if (CAN_InitStruct->CAN_NART == ENABLE) + { + CANx->MCR |= CAN_MCR_NART; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_NART; + } + + /* Set the receive FIFO locked mode */ + if (CAN_InitStruct->CAN_RFLM == ENABLE) + { + CANx->MCR |= CAN_MCR_RFLM; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_RFLM; + } + + /* Set the transmit FIFO priority */ + if (CAN_InitStruct->CAN_TXFP == ENABLE) + { + CANx->MCR |= CAN_MCR_TXFP; + } + else + { + CANx->MCR &= ~(uint32_t)CAN_MCR_TXFP; + } + + /* Set the bit timing register */ + CANx->BTR = (uint32_t)((uint32_t)CAN_InitStruct->CAN_Mode << 30) | \ + ((uint32_t)CAN_InitStruct->CAN_SJW << 24) | \ + ((uint32_t)CAN_InitStruct->CAN_BS1 << 16) | \ + ((uint32_t)CAN_InitStruct->CAN_BS2 << 20) | \ + ((uint32_t)CAN_InitStruct->CAN_Prescaler - 1); + + /* Request leave initialisation */ + CANx->MCR &= ~(uint32_t)CAN_MCR_INRQ; + + /* Wait the acknowledge */ + wait_ack = 0; + + while (((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) && (wait_ack != INAK_TIMEOUT)) + { + wait_ack++; + } + + /* ...and check acknowledged */ + if ((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK) + { + InitStatus = CAN_InitStatus_Failed; + } + else + { + InitStatus = CAN_InitStatus_Success ; + } + } + + /* At this step, return the status of initialization */ + return InitStatus; +} + +/** + * @brief Initializes the CAN peripheral according to the specified + * parameters in the CAN_FilterInitStruct. + * @param CAN_FilterInitStruct: pointer to a CAN_FilterInitTypeDef + * structure that contains the configuration + * information. + * @retval None. + */ +void CAN_FilterInit(CAN_FilterInitTypeDef* CAN_FilterInitStruct) +{ + uint32_t filter_number_bit_pos = 0; + /* Check the parameters */ + assert_param(IS_CAN_FILTER_NUMBER(CAN_FilterInitStruct->CAN_FilterNumber)); + assert_param(IS_CAN_FILTER_MODE(CAN_FilterInitStruct->CAN_FilterMode)); + assert_param(IS_CAN_FILTER_SCALE(CAN_FilterInitStruct->CAN_FilterScale)); + assert_param(IS_CAN_FILTER_FIFO(CAN_FilterInitStruct->CAN_FilterFIFOAssignment)); + assert_param(IS_FUNCTIONAL_STATE(CAN_FilterInitStruct->CAN_FilterActivation)); + + filter_number_bit_pos = ((uint32_t)1) << CAN_FilterInitStruct->CAN_FilterNumber; + + /* Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Filter Deactivation */ + CAN1->FA1R &= ~(uint32_t)filter_number_bit_pos; + + /* Filter Scale */ + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_16bit) + { + /* 16-bit scale for the filter */ + CAN1->FS1R &= ~(uint32_t)filter_number_bit_pos; + + /* First 16-bit identifier and First 16-bit mask */ + /* Or First 16-bit identifier and Second 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + + /* Second 16-bit identifier and Second 16-bit mask */ + /* Or Third 16-bit identifier and Fourth 16-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh); + } + + if (CAN_FilterInitStruct->CAN_FilterScale == CAN_FilterScale_32bit) + { + /* 32-bit scale for the filter */ + CAN1->FS1R |= filter_number_bit_pos; + /* 32-bit identifier or First 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR1 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterIdLow); + /* 32-bit mask or Second 32-bit identifier */ + CAN1->sFilterRegister[CAN_FilterInitStruct->CAN_FilterNumber].FR2 = + ((0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdHigh) << 16) | + (0x0000FFFF & (uint32_t)CAN_FilterInitStruct->CAN_FilterMaskIdLow); + } + + /* Filter Mode */ + if (CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdMask) + { + /*Id/Mask mode for the filter*/ + CAN1->FM1R &= ~(uint32_t)filter_number_bit_pos; + } + else /* CAN_FilterInitStruct->CAN_FilterMode == CAN_FilterMode_IdList */ + { + /*Identifier list mode for the filter*/ + CAN1->FM1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter FIFO assignment */ + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO0) + { + /* FIFO 0 assignation for the filter */ + CAN1->FFA1R &= ~(uint32_t)filter_number_bit_pos; + } + + if (CAN_FilterInitStruct->CAN_FilterFIFOAssignment == CAN_Filter_FIFO1) + { + /* FIFO 1 assignation for the filter */ + CAN1->FFA1R |= (uint32_t)filter_number_bit_pos; + } + + /* Filter activation */ + if (CAN_FilterInitStruct->CAN_FilterActivation == ENABLE) + { + CAN1->FA1R |= filter_number_bit_pos; + } + + /* Leave the initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Fills each CAN_InitStruct member with its default value. + * @param CAN_InitStruct: pointer to a CAN_InitTypeDef structure which + * will be initialized. + * @retval None. + */ +void CAN_StructInit(CAN_InitTypeDef* CAN_InitStruct) +{ + /* Reset CAN init structure parameters values */ + + /* Initialize the time triggered communication mode */ + CAN_InitStruct->CAN_TTCM = DISABLE; + + /* Initialize the automatic bus-off management */ + CAN_InitStruct->CAN_ABOM = DISABLE; + + /* Initialize the automatic wake-up mode */ + CAN_InitStruct->CAN_AWUM = DISABLE; + + /* Initialize the no automatic retransmission */ + CAN_InitStruct->CAN_NART = DISABLE; + + /* Initialize the receive FIFO locked mode */ + CAN_InitStruct->CAN_RFLM = DISABLE; + + /* Initialize the transmit FIFO priority */ + CAN_InitStruct->CAN_TXFP = DISABLE; + + /* Initialize the CAN_Mode member */ + CAN_InitStruct->CAN_Mode = CAN_Mode_Normal; + + /* Initialize the CAN_SJW member */ + CAN_InitStruct->CAN_SJW = CAN_SJW_1tq; + + /* Initialize the CAN_BS1 member */ + CAN_InitStruct->CAN_BS1 = CAN_BS1_4tq; + + /* Initialize the CAN_BS2 member */ + CAN_InitStruct->CAN_BS2 = CAN_BS2_3tq; + + /* Initialize the CAN_Prescaler member */ + CAN_InitStruct->CAN_Prescaler = 1; +} + +/** + * @brief Select the start bank filter for slave CAN. + * @note This function applies only to STM32 Connectivity line devices. + * @param CAN_BankNumber: Select the start slave bank filter from 1..27. + * @retval None. + */ +void CAN_SlaveStartBank(uint8_t CAN_BankNumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_BANKNUMBER(CAN_BankNumber)); + + /* Enter Initialisation mode for the filter */ + CAN1->FMR |= FMR_FINIT; + + /* Select the start slave bank */ + CAN1->FMR &= (uint32_t)0xFFFFC0F1 ; + CAN1->FMR |= (uint32_t)(CAN_BankNumber)<<8; + + /* Leave Initialisation mode for the filter */ + CAN1->FMR &= ~FMR_FINIT; +} + +/** + * @brief Enables or disables the DBG Freeze for CAN. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState: new state of the CAN peripheral. This parameter can + * be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_DBGFreeze(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable Debug Freeze */ + CANx->MCR |= MCR_DBF; + } + else + { + /* Disable Debug Freeze */ + CANx->MCR &= ~MCR_DBF; + } +} + + +/** + * @brief Enables or disabes the CAN Time TriggerOperation communication mode. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param NewState : Mode new state , can be one of @ref FunctionalState. + * @note when enabled, Time stamp (TIME[15:0]) value is sent in the last + * two data bytes of the 8-byte message: TIME[7:0] in data byte 6 + * and TIME[15:8] in data byte 7 + * @note DLC must be programmed as 8 in order Time Stamp (2 bytes) to be + * sent over the CAN bus. + * @retval None + */ +void CAN_TTComModeCmd(CAN_TypeDef* CANx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TTCM mode */ + CANx->MCR |= CAN_MCR_TTCM; + + /* Set TGT bits */ + CANx->sTxMailBox[0].TDTR |= ((uint32_t)CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR |= ((uint32_t)CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR |= ((uint32_t)CAN_TDT2R_TGT); + } + else + { + /* Disable the TTCM mode */ + CANx->MCR &= (uint32_t)(~(uint32_t)CAN_MCR_TTCM); + + /* Reset TGT bits */ + CANx->sTxMailBox[0].TDTR &= ((uint32_t)~CAN_TDT0R_TGT); + CANx->sTxMailBox[1].TDTR &= ((uint32_t)~CAN_TDT1R_TGT); + CANx->sTxMailBox[2].TDTR &= ((uint32_t)~CAN_TDT2R_TGT); + } +} +/** + * @brief Initiates the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param TxMessage: pointer to a structure which contains CAN Id, CAN + * DLC and CAN data. + * @retval The number of the mailbox that is used for transmission + * or CAN_TxStatus_NoMailBox if there is no empty mailbox. + */ +uint8_t CAN_Transmit(CAN_TypeDef* CANx, CanTxMsg* TxMessage) +{ + uint8_t transmit_mailbox = 0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IDTYPE(TxMessage->IDE)); + assert_param(IS_CAN_RTR(TxMessage->RTR)); + assert_param(IS_CAN_DLC(TxMessage->DLC)); + + /* Select one empty transmit mailbox */ + if ((CANx->TSR&CAN_TSR_TME0) == CAN_TSR_TME0) + { + transmit_mailbox = 0; + } + else if ((CANx->TSR&CAN_TSR_TME1) == CAN_TSR_TME1) + { + transmit_mailbox = 1; + } + else if ((CANx->TSR&CAN_TSR_TME2) == CAN_TSR_TME2) + { + transmit_mailbox = 2; + } + else + { + transmit_mailbox = CAN_TxStatus_NoMailBox; + } + + if (transmit_mailbox != CAN_TxStatus_NoMailBox) + { + /* Set up the Id */ + CANx->sTxMailBox[transmit_mailbox].TIR &= TMIDxR_TXRQ; + if (TxMessage->IDE == CAN_Id_Standard) + { + assert_param(IS_CAN_STDID(TxMessage->StdId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->StdId << 21) | \ + TxMessage->RTR); + } + else + { + assert_param(IS_CAN_EXTID(TxMessage->ExtId)); + CANx->sTxMailBox[transmit_mailbox].TIR |= ((TxMessage->ExtId << 3) | \ + TxMessage->IDE | \ + TxMessage->RTR); + } + + /* Set up the DLC */ + TxMessage->DLC &= (uint8_t)0x0000000F; + CANx->sTxMailBox[transmit_mailbox].TDTR &= (uint32_t)0xFFFFFFF0; + CANx->sTxMailBox[transmit_mailbox].TDTR |= TxMessage->DLC; + + /* Set up the data field */ + CANx->sTxMailBox[transmit_mailbox].TDLR = (((uint32_t)TxMessage->Data[3] << 24) | + ((uint32_t)TxMessage->Data[2] << 16) | + ((uint32_t)TxMessage->Data[1] << 8) | + ((uint32_t)TxMessage->Data[0])); + CANx->sTxMailBox[transmit_mailbox].TDHR = (((uint32_t)TxMessage->Data[7] << 24) | + ((uint32_t)TxMessage->Data[6] << 16) | + ((uint32_t)TxMessage->Data[5] << 8) | + ((uint32_t)TxMessage->Data[4])); + /* Request transmission */ + CANx->sTxMailBox[transmit_mailbox].TIR |= TMIDxR_TXRQ; + } + return transmit_mailbox; +} + +/** + * @brief Checks the transmission of a message. + * @param CANx: where x can be 1 or 2 to to select the + * CAN peripheral. + * @param TransmitMailbox: the number of the mailbox that is used for + * transmission. + * @retval CAN_TxStatus_Ok if the CAN driver transmits the message, CAN_TxStatus_Failed + * in an other case. + */ +uint8_t CAN_TransmitStatus(CAN_TypeDef* CANx, uint8_t TransmitMailbox) +{ + uint32_t state = 0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(TransmitMailbox)); + + switch (TransmitMailbox) + { + case (CAN_TXMAILBOX_0): + state = CANx->TSR & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0); + break; + case (CAN_TXMAILBOX_1): + state = CANx->TSR & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1); + break; + case (CAN_TXMAILBOX_2): + state = CANx->TSR & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2); + break; + default: + state = CAN_TxStatus_Failed; + break; + } + switch (state) + { + /* transmit pending */ + case (0x0): state = CAN_TxStatus_Pending; + break; + /* transmit failed */ + case (CAN_TSR_RQCP0 | CAN_TSR_TME0): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TME1): state = CAN_TxStatus_Failed; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TME2): state = CAN_TxStatus_Failed; + break; + /* transmit succeeded */ + case (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1):state = CAN_TxStatus_Ok; + break; + case (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2):state = CAN_TxStatus_Ok; + break; + default: state = CAN_TxStatus_Failed; + break; + } + return (uint8_t) state; +} + +/** + * @brief Cancels a transmit request. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param Mailbox: Mailbox number. + * @retval None. + */ +void CAN_CancelTransmit(CAN_TypeDef* CANx, uint8_t Mailbox) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_TRANSMITMAILBOX(Mailbox)); + /* abort transmission */ + switch (Mailbox) + { + case (CAN_TXMAILBOX_0): CANx->TSR |= CAN_TSR_ABRQ0; + break; + case (CAN_TXMAILBOX_1): CANx->TSR |= CAN_TSR_ABRQ1; + break; + case (CAN_TXMAILBOX_2): CANx->TSR |= CAN_TSR_ABRQ2; + break; + default: + break; + } +} + + +/** + * @brief Receives a message. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @param RxMessage: pointer to a structure receive message which contains + * CAN Id, CAN DLC, CAN datas and FMI number. + * @retval None. + */ +void CAN_Receive(CAN_TypeDef* CANx, uint8_t FIFONumber, CanRxMsg* RxMessage) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Get the Id */ + RxMessage->IDE = (uint8_t)0x04 & CANx->sFIFOMailBox[FIFONumber].RIR; + if (RxMessage->IDE == CAN_Id_Standard) + { + RxMessage->StdId = (uint32_t)0x000007FF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 21); + } + else + { + RxMessage->ExtId = (uint32_t)0x1FFFFFFF & (CANx->sFIFOMailBox[FIFONumber].RIR >> 3); + } + + RxMessage->RTR = (uint8_t)0x02 & CANx->sFIFOMailBox[FIFONumber].RIR; + /* Get the DLC */ + RxMessage->DLC = (uint8_t)0x0F & CANx->sFIFOMailBox[FIFONumber].RDTR; + /* Get the FMI */ + RxMessage->FMI = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDTR >> 8); + /* Get the data field */ + RxMessage->Data[0] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDLR; + RxMessage->Data[1] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 8); + RxMessage->Data[2] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 16); + RxMessage->Data[3] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDLR >> 24); + RxMessage->Data[4] = (uint8_t)0xFF & CANx->sFIFOMailBox[FIFONumber].RDHR; + RxMessage->Data[5] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 8); + RxMessage->Data[6] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 16); + RxMessage->Data[7] = (uint8_t)0xFF & (CANx->sFIFOMailBox[FIFONumber].RDHR >> 24); + /* Release the FIFO */ + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Releases the specified FIFO. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: FIFO to release, CAN_FIFO0 or CAN_FIFO1. + * @retval None. + */ +void CAN_FIFORelease(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + /* Release FIFO0 */ + if (FIFONumber == CAN_FIFO0) + { + CANx->RF0R |= CAN_RF0R_RFOM0; + } + /* Release FIFO1 */ + else /* FIFONumber == CAN_FIFO1 */ + { + CANx->RF1R |= CAN_RF1R_RFOM1; + } +} + +/** + * @brief Returns the number of pending messages. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param FIFONumber: Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. + * @retval NbMessage : which is the number of pending message. + */ +uint8_t CAN_MessagePending(CAN_TypeDef* CANx, uint8_t FIFONumber) +{ + uint8_t message_pending=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_FIFO(FIFONumber)); + if (FIFONumber == CAN_FIFO0) + { + message_pending = (uint8_t)(CANx->RF0R&(uint32_t)0x03); + } + else if (FIFONumber == CAN_FIFO1) + { + message_pending = (uint8_t)(CANx->RF1R&(uint32_t)0x03); + } + else + { + message_pending = 0; + } + return message_pending; +} + + +/** + * @brief Select the CAN Operation mode. + * @param CAN_OperatingMode : CAN Operating Mode. This parameter can be one + * of @ref CAN_OperatingMode_TypeDef enumeration. + * @retval status of the requested mode which can be + * - CAN_ModeStatus_Failed CAN failed entering the specific mode + * - CAN_ModeStatus_Success CAN Succeed entering the specific mode + + */ +uint8_t CAN_OperatingModeRequest(CAN_TypeDef* CANx, uint8_t CAN_OperatingMode) +{ + uint8_t status = CAN_ModeStatus_Failed; + + /* Timeout for INAK or also for SLAK bits*/ + uint32_t timeout = INAK_TIMEOUT; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_OPERATING_MODE(CAN_OperatingMode)); + + if (CAN_OperatingMode == CAN_OperatingMode_Initialization) + { + /* Request initialisation */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_SLEEP)) | CAN_MCR_INRQ); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) && (timeout != 0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_INAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Normal) + { + /* Request leave initialisation and sleep mode and enter Normal mode */ + CANx->MCR &= (uint32_t)(~(CAN_MCR_SLEEP|CAN_MCR_INRQ)); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != 0) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != 0) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else if (CAN_OperatingMode == CAN_OperatingMode_Sleep) + { + /* Request Sleep mode */ + CANx->MCR = (uint32_t)((CANx->MCR & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Wait the acknowledge */ + while (((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) && (timeout!=0)) + { + timeout--; + } + if ((CANx->MSR & CAN_MODE_MASK) != CAN_MSR_SLAK) + { + status = CAN_ModeStatus_Failed; + } + else + { + status = CAN_ModeStatus_Success; + } + } + else + { + status = CAN_ModeStatus_Failed; + } + + return (uint8_t) status; +} + +/** + * @brief Enters the low power mode. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval status: CAN_Sleep_Ok if sleep entered, CAN_Sleep_Failed in an + * other case. + */ +uint8_t CAN_Sleep(CAN_TypeDef* CANx) +{ + uint8_t sleepstatus = CAN_Sleep_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Request Sleep mode */ + CANx->MCR = (((CANx->MCR) & (uint32_t)(~(uint32_t)CAN_MCR_INRQ)) | CAN_MCR_SLEEP); + + /* Sleep mode status */ + if ((CANx->MSR & (CAN_MSR_SLAK|CAN_MSR_INAK)) == CAN_MSR_SLAK) + { + /* Sleep mode not entered */ + sleepstatus = CAN_Sleep_Ok; + } + /* return sleep mode status */ + return (uint8_t)sleepstatus; +} + +/** + * @brief Wakes the CAN up. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval status: CAN_WakeUp_Ok if sleep mode left, CAN_WakeUp_Failed in an + * other case. + */ +uint8_t CAN_WakeUp(CAN_TypeDef* CANx) +{ + uint32_t wait_slak = SLAK_TIMEOUT; + uint8_t wakeupstatus = CAN_WakeUp_Failed; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Wake up request */ + CANx->MCR &= ~(uint32_t)CAN_MCR_SLEEP; + + /* Sleep mode status */ + while(((CANx->MSR & CAN_MSR_SLAK) == CAN_MSR_SLAK)&&(wait_slak!=0x00)) + { + wait_slak--; + } + if((CANx->MSR & CAN_MSR_SLAK) != CAN_MSR_SLAK) + { + /* wake up done : Sleep mode exited */ + wakeupstatus = CAN_WakeUp_Ok; + } + /* return wakeup status */ + return (uint8_t)wakeupstatus; +} + + +/** + * @brief Returns the CANx's last error code (LEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN_ErrorCode: specifies the Error code : + * - CAN_ERRORCODE_NoErr No Error + * - CAN_ERRORCODE_StuffErr Stuff Error + * - CAN_ERRORCODE_FormErr Form Error + * - CAN_ERRORCODE_ACKErr Acknowledgment Error + * - CAN_ERRORCODE_BitRecessiveErr Bit Recessive Error + * - CAN_ERRORCODE_BitDominantErr Bit Dominant Error + * - CAN_ERRORCODE_CRCErr CRC Error + * - CAN_ERRORCODE_SoftwareSetErr Software Set Error + */ + +uint8_t CAN_GetLastErrorCode(CAN_TypeDef* CANx) +{ + uint8_t errorcode=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the error code*/ + errorcode = (((uint8_t)CANx->ESR) & (uint8_t)CAN_ESR_LEC); + + /* Return the error code*/ + return errorcode; +} +/** + * @brief Returns the CANx Receive Error Counter (REC). + * @note In case of an error during reception, this counter is incremented + * by 1 or by 8 depending on the error condition as defined by the CAN + * standard. After every successful reception, the counter is + * decremented by 1 or reset to 120 if its value was higher than 128. + * When the counter value exceeds 127, the CAN controller enters the + * error passive state. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval CAN Receive Error Counter. + */ +uint8_t CAN_GetReceiveErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the Receive Error Counter*/ + counter = (uint8_t)((CANx->ESR & CAN_ESR_REC)>> 24); + + /* Return the Receive Error Counter*/ + return counter; +} + + +/** + * @brief Returns the LSB of the 9-bit CANx Transmit Error Counter(TEC). + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @retval LSB of the 9-bit CAN Transmit Error Counter. + */ +uint8_t CAN_GetLSBTransmitErrorCounter(CAN_TypeDef* CANx) +{ + uint8_t counter=0; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + + /* Get the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + counter = (uint8_t)((CANx->ESR & CAN_ESR_TEC)>> 16); + + /* Return the LSB of the 9-bit CANx Transmit Error Counter(TEC) */ + return counter; +} + + +/** + * @brief Enables or disables the specified CANx interrupts. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt sources to be enabled or disabled. + * This parameter can be: + * - CAN_IT_TME, + * - CAN_IT_FMP0, + * - CAN_IT_FF0, + * - CAN_IT_FOV0, + * - CAN_IT_FMP1, + * - CAN_IT_FF1, + * - CAN_IT_FOV1, + * - CAN_IT_EWG, + * - CAN_IT_EPV, + * - CAN_IT_LEC, + * - CAN_IT_ERR, + * - CAN_IT_WKU or + * - CAN_IT_SLK. + * @param NewState: new state of the CAN interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void CAN_ITConfig(CAN_TypeDef* CANx, uint32_t CAN_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected CANx interrupt */ + CANx->IER |= CAN_IT; + } + else + { + /* Disable the selected CANx interrupt */ + CANx->IER &= ~CAN_IT; + } +} +/** + * @brief Checks whether the specified CAN flag is set or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to check. + * This parameter can be one of the following flags: + * - CAN_FLAG_EWG + * - CAN_FLAG_EPV + * - CAN_FLAG_BOF + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FMP1 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FMP0 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval The new state of CAN_FLAG (SET or RESET). + */ +FlagStatus CAN_GetFlagStatus(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_GET_FLAG(CAN_FLAG)); + + + if((CAN_FLAG & CAN_FLAGS_ESR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->ESR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_MSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->MSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_TSR) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->TSR & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else if((CAN_FLAG & CAN_FLAGS_RF0R) != (uint32_t)RESET) + { + /* Check the status of the specified CAN flag */ + if ((CANx->RF0R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + else /* If(CAN_FLAG & CAN_FLAGS_RF1R != (uint32_t)RESET) */ + { + /* Check the status of the specified CAN flag */ + if ((uint32_t)(CANx->RF1R & (CAN_FLAG & 0x000FFFFF)) != (uint32_t)RESET) + { + /* CAN_FLAG is set */ + bitstatus = SET; + } + else + { + /* CAN_FLAG is reset */ + bitstatus = RESET; + } + } + /* Return the CAN_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CAN's pending flags. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_FLAG: specifies the flag to clear. + * This parameter can be one of the following flags: + * - CAN_FLAG_RQCP0 + * - CAN_FLAG_RQCP1 + * - CAN_FLAG_RQCP2 + * - CAN_FLAG_FF1 + * - CAN_FLAG_FOV1 + * - CAN_FLAG_FF0 + * - CAN_FLAG_FOV0 + * - CAN_FLAG_WKU + * - CAN_FLAG_SLAK + * - CAN_FLAG_LEC + * @retval None. + */ +void CAN_ClearFlag(CAN_TypeDef* CANx, uint32_t CAN_FLAG) +{ + uint32_t flagtmp=0; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_FLAG(CAN_FLAG)); + + if (CAN_FLAG == CAN_FLAG_LEC) /* ESR register */ + { + /* Clear the selected CAN flags */ + CANx->ESR = (uint32_t)RESET; + } + else /* MSR or TSR or RF0R or RF1R */ + { + flagtmp = CAN_FLAG & 0x000FFFFF; + + if ((CAN_FLAG & CAN_FLAGS_RF0R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF0R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_RF1R)!=(uint32_t)RESET) + { + /* Receive Flags */ + CANx->RF1R = (uint32_t)(flagtmp); + } + else if ((CAN_FLAG & CAN_FLAGS_TSR)!=(uint32_t)RESET) + { + /* Transmit Flags */ + CANx->TSR = (uint32_t)(flagtmp); + } + else /* If((CAN_FLAG & CAN_FLAGS_MSR)!=(uint32_t)RESET) */ + { + /* Operating mode Flags */ + CANx->MSR = (uint32_t)(flagtmp); + } + } +} + +/** + * @brief Checks whether the specified CANx interrupt has occurred or not. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the CAN interrupt source to check. + * This parameter can be one of the following flags: + * - CAN_IT_TME + * - CAN_IT_FMP0 + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FMP1 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval The current state of CAN_IT (SET or RESET). + */ +ITStatus CAN_GetITStatus(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + ITStatus itstatus = RESET; + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_IT(CAN_IT)); + + /* check the enable interrupt bit */ + if((CANx->IER & CAN_IT) != RESET) + { + /* in case the Interrupt is enabled, .... */ + switch (CAN_IT) + { + case CAN_IT_TME: + /* Check CAN_TSR_RQCPx bits */ + itstatus = CheckITStatus(CANx->TSR, CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2); + break; + case CAN_IT_FMP0: + /* Check CAN_RF0R_FMP0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FMP0); + break; + case CAN_IT_FF0: + /* Check CAN_RF0R_FULL0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FULL0); + break; + case CAN_IT_FOV0: + /* Check CAN_RF0R_FOVR0 bit */ + itstatus = CheckITStatus(CANx->RF0R, CAN_RF0R_FOVR0); + break; + case CAN_IT_FMP1: + /* Check CAN_RF1R_FMP1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FMP1); + break; + case CAN_IT_FF1: + /* Check CAN_RF1R_FULL1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FULL1); + break; + case CAN_IT_FOV1: + /* Check CAN_RF1R_FOVR1 bit */ + itstatus = CheckITStatus(CANx->RF1R, CAN_RF1R_FOVR1); + break; + case CAN_IT_WKU: + /* Check CAN_MSR_WKUI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_WKUI); + break; + case CAN_IT_SLK: + /* Check CAN_MSR_SLAKI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_SLAKI); + break; + case CAN_IT_EWG: + /* Check CAN_ESR_EWGF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EWGF); + break; + case CAN_IT_EPV: + /* Check CAN_ESR_EPVF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_EPVF); + break; + case CAN_IT_BOF: + /* Check CAN_ESR_BOFF bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_BOFF); + break; + case CAN_IT_LEC: + /* Check CAN_ESR_LEC bit */ + itstatus = CheckITStatus(CANx->ESR, CAN_ESR_LEC); + break; + case CAN_IT_ERR: + /* Check CAN_MSR_ERRI bit */ + itstatus = CheckITStatus(CANx->MSR, CAN_MSR_ERRI); + break; + default : + /* in case of error, return RESET */ + itstatus = RESET; + break; + } + } + else + { + /* in case the Interrupt is not enabled, return RESET */ + itstatus = RESET; + } + + /* Return the CAN_IT status */ + return itstatus; +} + +/** + * @brief Clears the CANx's interrupt pending bits. + * @param CANx: where x can be 1 or 2 to to select the CAN peripheral. + * @param CAN_IT: specifies the interrupt pending bit to clear. + * - CAN_IT_TME + * - CAN_IT_FF0 + * - CAN_IT_FOV0 + * - CAN_IT_FF1 + * - CAN_IT_FOV1 + * - CAN_IT_WKU + * - CAN_IT_SLK + * - CAN_IT_EWG + * - CAN_IT_EPV + * - CAN_IT_BOF + * - CAN_IT_LEC + * - CAN_IT_ERR + * @retval None. + */ +void CAN_ClearITPendingBit(CAN_TypeDef* CANx, uint32_t CAN_IT) +{ + /* Check the parameters */ + assert_param(IS_CAN_ALL_PERIPH(CANx)); + assert_param(IS_CAN_CLEAR_IT(CAN_IT)); + + switch (CAN_IT) + { + case CAN_IT_TME: + /* Clear CAN_TSR_RQCPx (rc_w1)*/ + CANx->TSR = CAN_TSR_RQCP0|CAN_TSR_RQCP1|CAN_TSR_RQCP2; + break; + case CAN_IT_FF0: + /* Clear CAN_RF0R_FULL0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FULL0; + break; + case CAN_IT_FOV0: + /* Clear CAN_RF0R_FOVR0 (rc_w1)*/ + CANx->RF0R = CAN_RF0R_FOVR0; + break; + case CAN_IT_FF1: + /* Clear CAN_RF1R_FULL1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FULL1; + break; + case CAN_IT_FOV1: + /* Clear CAN_RF1R_FOVR1 (rc_w1)*/ + CANx->RF1R = CAN_RF1R_FOVR1; + break; + case CAN_IT_WKU: + /* Clear CAN_MSR_WKUI (rc_w1)*/ + CANx->MSR = CAN_MSR_WKUI; + break; + case CAN_IT_SLK: + /* Clear CAN_MSR_SLAKI (rc_w1)*/ + CANx->MSR = CAN_MSR_SLAKI; + break; + case CAN_IT_EWG: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_EPV: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_BOF: + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : the corresponding Flag is cleared by hardware depending + of the CAN Bus status*/ + break; + case CAN_IT_LEC: + /* Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + break; + case CAN_IT_ERR: + /*Clear LEC bits */ + CANx->ESR = RESET; + /* Clear CAN_MSR_ERRI (rc_w1) */ + CANx->MSR = CAN_MSR_ERRI; + /* Note : BOFF, EPVF and EWGF Flags are cleared by hardware depending + of the CAN Bus status*/ + break; + default : + break; + } +} + +/** + * @brief Checks whether the CAN interrupt has occurred or not. + * @param CAN_Reg: specifies the CAN interrupt register to check. + * @param It_Bit: specifies the interrupt source bit to check. + * @retval The new state of the CAN Interrupt (SET or RESET). + */ +static ITStatus CheckITStatus(uint32_t CAN_Reg, uint32_t It_Bit) +{ + ITStatus pendingbitstatus = RESET; + + if ((CAN_Reg & It_Bit) != (uint32_t)RESET) + { + /* CAN_IT is set */ + pendingbitstatus = SET; + } + else + { + /* CAN_IT is reset */ + pendingbitstatus = RESET; + } + return pendingbitstatus; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c new file mode 100755 index 0000000000..08b501a0c4 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_cec.c @@ -0,0 +1,433 @@ +/** + ****************************************************************************** + * @file stm32f10x_cec.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CEC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_cec.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CEC + * @brief CEC driver modules + * @{ + */ + +/** @defgroup CEC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Defines + * @{ + */ + +/* ------------ CEC registers bit address in the alias region ----------- */ +#define CEC_OFFSET (CEC_BASE - PERIPH_BASE) + +/* --- CFGR Register ---*/ + +/* Alias word address of PE bit */ +#define CFGR_OFFSET (CEC_OFFSET + 0x00) +#define PE_BitNumber 0x00 +#define CFGR_PE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (PE_BitNumber * 4)) + +/* Alias word address of IE bit */ +#define IE_BitNumber 0x01 +#define CFGR_IE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (IE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of TSOM bit */ +#define CSR_OFFSET (CEC_OFFSET + 0x10) +#define TSOM_BitNumber 0x00 +#define CSR_TSOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TSOM_BitNumber * 4)) + +/* Alias word address of TEOM bit */ +#define TEOM_BitNumber 0x01 +#define CSR_TEOM_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (TEOM_BitNumber * 4)) + +#define CFGR_CLEAR_Mask (uint8_t)(0xF3) /* CFGR register Mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) /* CEC FLAG mask */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Macros + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Variables + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + + +/** @defgroup CEC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the CEC peripheral registers to their default reset + * values. + * @param None + * @retval None + */ +void CEC_DeInit(void) +{ + /* Enable CEC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, ENABLE); + /* Release CEC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_CEC, DISABLE); +} + + +/** + * @brief Initializes the CEC peripheral according to the specified + * parameters in the CEC_InitStruct. + * @param CEC_InitStruct: pointer to an CEC_InitTypeDef structure that + * contains the configuration information for the specified + * CEC peripheral. + * @retval None + */ +void CEC_Init(CEC_InitTypeDef* CEC_InitStruct) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_CEC_BIT_TIMING_ERROR_MODE(CEC_InitStruct->CEC_BitTimingMode)); + assert_param(IS_CEC_BIT_PERIOD_ERROR_MODE(CEC_InitStruct->CEC_BitPeriodMode)); + + /*---------------------------- CEC CFGR Configuration -----------------*/ + /* Get the CEC CFGR value */ + tmpreg = CEC->CFGR; + + /* Clear BTEM and BPEM bits */ + tmpreg &= CFGR_CLEAR_Mask; + + /* Configure CEC: Bit Timing Error and Bit Period Error */ + tmpreg |= (uint16_t)(CEC_InitStruct->CEC_BitTimingMode | CEC_InitStruct->CEC_BitPeriodMode); + + /* Write to CEC CFGR register*/ + CEC->CFGR = tmpreg; + +} + +/** + * @brief Enables or disables the specified CEC peripheral. + * @param NewState: new state of the CEC peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_PE_BB = (uint32_t)NewState; + + if(NewState == DISABLE) + { + /* Wait until the PE bit is cleared by hardware (Idle Line detected) */ + while((CEC->CFGR & CEC_CFGR_PE) != (uint32_t)RESET) + { + } + } +} + +/** + * @brief Enables or disables the CEC interrupt. + * @param NewState: new state of the CEC interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_ITConfig(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CFGR_IE_BB = (uint32_t)NewState; +} + +/** + * @brief Defines the Own Address of the CEC device. + * @param CEC_OwnAddress: The CEC own address + * @retval None + */ +void CEC_OwnAddressConfig(uint8_t CEC_OwnAddress) +{ + /* Check the parameters */ + assert_param(IS_CEC_ADDRESS(CEC_OwnAddress)); + + /* Set the CEC own address */ + CEC->OAR = CEC_OwnAddress; +} + +/** + * @brief Sets the CEC prescaler value. + * @param CEC_Prescaler: CEC prescaler new value + * @retval None + */ +void CEC_SetPrescaler(uint16_t CEC_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_CEC_PRESCALER(CEC_Prescaler)); + + /* Set the Prescaler value*/ + CEC->PRES = CEC_Prescaler; +} + +/** + * @brief Transmits single data through the CEC peripheral. + * @param Data: the data to transmit. + * @retval None + */ +void CEC_SendDataByte(uint8_t Data) +{ + /* Transmit Data */ + CEC->TXD = Data ; +} + + +/** + * @brief Returns the most recent received data by the CEC peripheral. + * @param None + * @retval The received data. + */ +uint8_t CEC_ReceiveDataByte(void) +{ + /* Receive Data */ + return (uint8_t)(CEC->RXD); +} + +/** + * @brief Starts a new message. + * @param None + * @retval None + */ +void CEC_StartOfMessage(void) +{ + /* Starts of new message */ + *(__IO uint32_t *) CSR_TSOM_BB = (uint32_t)0x1; +} + +/** + * @brief Transmits message with or without an EOM bit. + * @param NewState: new state of the CEC Tx End Of Message. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void CEC_EndOfMessageCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + /* The data byte will be transmitted with or without an EOM bit*/ + *(__IO uint32_t *) CSR_TEOM_BB = (uint32_t)NewState; +} + +/** + * @brief Gets the CEC flag status + * @param CEC_FLAG: specifies the CEC flag to check. + * This parameter can be one of the following values: + * @arg CEC_FLAG_BTE: Bit Timing Error + * @arg CEC_FLAG_BPE: Bit Period Error + * @arg CEC_FLAG_RBTFE: Rx Block Transfer Finished Error + * @arg CEC_FLAG_SBE: Start Bit Error + * @arg CEC_FLAG_ACKE: Block Acknowledge Error + * @arg CEC_FLAG_LINE: Line Error + * @arg CEC_FLAG_TBTFE: Tx Block Transfer Finished Error + * @arg CEC_FLAG_TEOM: Tx End Of Message + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval The new state of CEC_FLAG (SET or RESET) + */ +FlagStatus CEC_GetFlagStatus(uint32_t CEC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t cecreg = 0, cecbase = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_FLAG(CEC_FLAG)); + + /* Get the CEC peripheral base address */ + cecbase = (uint32_t)(CEC_BASE); + + /* Read flag register index */ + cecreg = CEC_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + CEC_FLAG &= FLAG_Mask; + + if(cecreg != 0) + { + /* Flag in CEC ESR Register */ + CEC_FLAG = (uint32_t)(CEC_FLAG >> 16); + + /* Get the CEC ESR register address */ + cecbase += 0xC; + } + else + { + /* Get the CEC CSR register address */ + cecbase += 0x10; + } + + if(((*(__IO uint32_t *)cecbase) & CEC_FLAG) != (uint32_t)RESET) + { + /* CEC_FLAG is set */ + bitstatus = SET; + } + else + { + /* CEC_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the CEC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's pending flags. + * @param CEC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg CEC_FLAG_TERR: Tx Error + * @arg CEC_FLAG_TBTRF: Tx Byte Transfer Request or Block Transfer Finished + * @arg CEC_FLAG_RSOM: Rx Start Of Message + * @arg CEC_FLAG_REOM: Rx End Of Message + * @arg CEC_FLAG_RERR: Rx Error + * @arg CEC_FLAG_RBTF: Rx Byte/Block Transfer Finished + * @retval None + */ +void CEC_ClearFlag(uint32_t CEC_FLAG) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_CLEAR_FLAG(CEC_FLAG)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC flags */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_FLAG) & 0xFFFFFFFC) | tmp); +} + +/** + * @brief Checks whether the specified CEC interrupt has occurred or not. + * @param CEC_IT: specifies the CEC interrupt source to check. + * This parameter can be one of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval The new state of CEC_IT (SET or RESET). + */ +ITStatus CEC_GetITStatus(uint8_t CEC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + /* Get the CEC IT enable bit status */ + enablestatus = (CEC->CFGR & (uint8_t)CEC_CFGR_IE) ; + + /* Check the status of the specified CEC interrupt */ + if (((CEC->CSR & CEC_IT) != (uint32_t)RESET) && enablestatus) + { + /* CEC_IT is set */ + bitstatus = SET; + } + else + { + /* CEC_IT is reset */ + bitstatus = RESET; + } + /* Return the CEC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the CEC's interrupt pending bits. + * @param CEC_IT: specifies the CEC interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg CEC_IT_TERR: Tx Error + * @arg CEC_IT_TBTF: Tx Block Transfer Finished + * @arg CEC_IT_RERR: Rx Error + * @arg CEC_IT_RBTF: Rx Block Transfer Finished + * @retval None + */ +void CEC_ClearITPendingBit(uint16_t CEC_IT) +{ + uint32_t tmp = 0x0; + + /* Check the parameters */ + assert_param(IS_CEC_GET_IT(CEC_IT)); + + tmp = CEC->CSR & 0x2; + + /* Clear the selected CEC interrupt pending bits */ + CEC->CSR &= (uint32_t)(((~(uint32_t)CEC_IT) & 0xFFFFFFFC) | tmp); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c new file mode 100755 index 0000000000..ef0c047d8f --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_crc.c @@ -0,0 +1,160 @@ +/** + ****************************************************************************** + * @file stm32f10x_crc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the CRC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_crc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup CRC + * @brief CRC driver modules + * @{ + */ + +/** @defgroup CRC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup CRC_Private_Functions + * @{ + */ + +/** + * @brief Resets the CRC Data register (DR). + * @param None + * @retval None + */ +void CRC_ResetDR(void) +{ + /* Reset CRC generator */ + CRC->CR = CRC_CR_RESET; +} + +/** + * @brief Computes the 32-bit CRC of a given data word(32-bit). + * @param Data: data word(32-bit) to compute its CRC + * @retval 32-bit CRC + */ +uint32_t CRC_CalcCRC(uint32_t Data) +{ + CRC->DR = Data; + + return (CRC->DR); +} + +/** + * @brief Computes the 32-bit CRC of a given buffer of data word(32-bit). + * @param pBuffer: pointer to the buffer containing the data to be computed + * @param BufferLength: length of the buffer to be computed + * @retval 32-bit CRC + */ +uint32_t CRC_CalcBlockCRC(uint32_t pBuffer[], uint32_t BufferLength) +{ + uint32_t index = 0; + + for(index = 0; index < BufferLength; index++) + { + CRC->DR = pBuffer[index]; + } + return (CRC->DR); +} + +/** + * @brief Returns the current CRC value. + * @param None + * @retval 32-bit CRC + */ +uint32_t CRC_GetCRC(void) +{ + return (CRC->DR); +} + +/** + * @brief Stores a 8-bit data in the Independent Data(ID) register. + * @param IDValue: 8-bit value to be stored in the ID register + * @retval None + */ +void CRC_SetIDRegister(uint8_t IDValue) +{ + CRC->IDR = IDValue; +} + +/** + * @brief Returns the 8-bit data stored in the Independent Data(ID) register + * @param None + * @retval 8-bit value of the ID register + */ +uint8_t CRC_GetIDRegister(void) +{ + return (CRC->IDR); +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c new file mode 100755 index 0000000000..025b8e2837 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dac.c @@ -0,0 +1,571 @@ +/** + ****************************************************************************** + * @file stm32f10x_dac.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DAC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dac.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DAC + * @brief DAC driver modules + * @{ + */ + +/** @defgroup DAC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Defines + * @{ + */ + +/* CR register Mask */ +#define CR_CLEAR_MASK ((uint32_t)0x00000FFE) + +/* DAC Dual Channels SWTRIG masks */ +#define DUAL_SWTRIG_SET ((uint32_t)0x00000003) +#define DUAL_SWTRIG_RESET ((uint32_t)0xFFFFFFFC) + +/* DHR registers offsets */ +#define DHR12R1_OFFSET ((uint32_t)0x00000008) +#define DHR12R2_OFFSET ((uint32_t)0x00000014) +#define DHR12RD_OFFSET ((uint32_t)0x00000020) + +/* DOR register offset */ +#define DOR_OFFSET ((uint32_t)0x0000002C) +/** + * @} + */ + +/** @defgroup DAC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DAC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DAC peripheral registers to their default reset values. + * @param None + * @retval None + */ +void DAC_DeInit(void) +{ + /* Enable DAC reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, ENABLE); + /* Release DAC from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_DAC, DISABLE); +} + +/** + * @brief Initializes the DAC peripheral according to the specified + * parameters in the DAC_InitStruct. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_InitStruct: pointer to a DAC_InitTypeDef structure that + * contains the configuration information for the specified DAC channel. + * @retval None + */ +void DAC_Init(uint32_t DAC_Channel, DAC_InitTypeDef* DAC_InitStruct) +{ + uint32_t tmpreg1 = 0, tmpreg2 = 0; + /* Check the DAC parameters */ + assert_param(IS_DAC_TRIGGER(DAC_InitStruct->DAC_Trigger)); + assert_param(IS_DAC_GENERATE_WAVE(DAC_InitStruct->DAC_WaveGeneration)); + assert_param(IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude)); + assert_param(IS_DAC_OUTPUT_BUFFER_STATE(DAC_InitStruct->DAC_OutputBuffer)); +/*---------------------------- DAC CR Configuration --------------------------*/ + /* Get the DAC CR value */ + tmpreg1 = DAC->CR; + /* Clear BOFFx, TENx, TSELx, WAVEx and MAMPx bits */ + tmpreg1 &= ~(CR_CLEAR_MASK << DAC_Channel); + /* Configure for the selected DAC channel: buffer output, trigger, wave generation, + mask/amplitude for wave generation */ + /* Set TSELx and TENx bits according to DAC_Trigger value */ + /* Set WAVEx bits according to DAC_WaveGeneration value */ + /* Set MAMPx bits according to DAC_LFSRUnmask_TriangleAmplitude value */ + /* Set BOFFx bit according to DAC_OutputBuffer value */ + tmpreg2 = (DAC_InitStruct->DAC_Trigger | DAC_InitStruct->DAC_WaveGeneration | + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude | DAC_InitStruct->DAC_OutputBuffer); + /* Calculate CR register value depending on DAC_Channel */ + tmpreg1 |= tmpreg2 << DAC_Channel; + /* Write to DAC CR */ + DAC->CR = tmpreg1; +} + +/** + * @brief Fills each DAC_InitStruct member with its default value. + * @param DAC_InitStruct : pointer to a DAC_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DAC_StructInit(DAC_InitTypeDef* DAC_InitStruct) +{ +/*--------------- Reset DAC init structure parameters values -----------------*/ + /* Initialize the DAC_Trigger member */ + DAC_InitStruct->DAC_Trigger = DAC_Trigger_None; + /* Initialize the DAC_WaveGeneration member */ + DAC_InitStruct->DAC_WaveGeneration = DAC_WaveGeneration_None; + /* Initialize the DAC_LFSRUnmask_TriangleAmplitude member */ + DAC_InitStruct->DAC_LFSRUnmask_TriangleAmplitude = DAC_LFSRUnmask_Bit0; + /* Initialize the DAC_OutputBuffer member */ + DAC_InitStruct->DAC_OutputBuffer = DAC_OutputBuffer_Enable; +} + +/** + * @brief Enables or disables the specified DAC channel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the DAC channel. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_Cmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel */ + DAC->CR |= (DAC_CR_EN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel */ + DAC->CR &= ~(DAC_CR_EN1 << DAC_Channel); + } +} +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Enables or disables the specified DAC interrupts. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt sources to be enabled or disabled. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @param NewState: new state of the specified DAC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_ITConfig(uint32_t DAC_Channel, uint32_t DAC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_DAC_IT(DAC_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected DAC interrupts */ + DAC->CR |= (DAC_IT << DAC_Channel); + } + else + { + /* Disable the selected DAC interrupts */ + DAC->CR &= (~(uint32_t)(DAC_IT << DAC_Channel)); + } +} +#endif + +/** + * @brief Enables or disables the specified DAC channel DMA request. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DMACmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DAC channel DMA request */ + DAC->CR |= (DAC_CR_DMAEN1 << DAC_Channel); + } + else + { + /* Disable the selected DAC channel DMA request */ + DAC->CR &= ~(DAC_CR_DMAEN1 << DAC_Channel); + } +} + +/** + * @brief Enables or disables the selected DAC channel software trigger. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param NewState: new state of the selected DAC channel software trigger. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_SoftwareTriggerCmd(uint32_t DAC_Channel, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for the selected DAC channel */ + DAC->SWTRIGR |= (uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4); + } + else + { + /* Disable software trigger for the selected DAC channel */ + DAC->SWTRIGR &= ~((uint32_t)DAC_SWTRIGR_SWTRIG1 << (DAC_Channel >> 4)); + } +} + +/** + * @brief Enables or disables simultaneously the two DAC channels software + * triggers. + * @param NewState: new state of the DAC channels software triggers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_DualSoftwareTriggerCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable software trigger for both DAC channels */ + DAC->SWTRIGR |= DUAL_SWTRIG_SET ; + } + else + { + /* Disable software trigger for both DAC channels */ + DAC->SWTRIGR &= DUAL_SWTRIG_RESET; + } +} + +/** + * @brief Enables or disables the selected DAC channel wave generation. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_Wave: Specifies the wave type to enable or disable. + * This parameter can be one of the following values: + * @arg DAC_Wave_Noise: noise wave generation + * @arg DAC_Wave_Triangle: triangle wave generation + * @param NewState: new state of the selected DAC channel wave generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DAC_WaveGenerationCmd(uint32_t DAC_Channel, uint32_t DAC_Wave, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_WAVE(DAC_Wave)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected wave generation for the selected DAC channel */ + DAC->CR |= DAC_Wave << DAC_Channel; + } + else + { + /* Disable the selected wave generation for the selected DAC channel */ + DAC->CR &= ~(DAC_Wave << DAC_Channel); + } +} + +/** + * @brief Set the specified data holding register value for DAC channel1. + * @param DAC_Align: Specifies the data alignment for DAC channel1. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel1Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R1_OFFSET + DAC_Align; + + /* Set the DAC channel1 selected data holding register */ + *(__IO uint32_t *) tmp = Data; +} + +/** + * @brief Set the specified data holding register value for DAC channel2. + * @param DAC_Align: Specifies the data alignment for DAC channel2. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data : Data to be loaded in the selected data holding register. + * @retval None + */ +void DAC_SetChannel2Data(uint32_t DAC_Align, uint16_t Data) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data)); + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12R2_OFFSET + DAC_Align; + + /* Set the DAC channel2 selected data holding register */ + *(__IO uint32_t *)tmp = Data; +} + +/** + * @brief Set the specified data holding register value for dual channel + * DAC. + * @param DAC_Align: Specifies the data alignment for dual channel DAC. + * This parameter can be one of the following values: + * @arg DAC_Align_8b_R: 8bit right data alignment selected + * @arg DAC_Align_12b_L: 12bit left data alignment selected + * @arg DAC_Align_12b_R: 12bit right data alignment selected + * @param Data2: Data for DAC Channel2 to be loaded in the selected data + * holding register. + * @param Data1: Data for DAC Channel1 to be loaded in the selected data + * holding register. + * @retval None + */ +void DAC_SetDualChannelData(uint32_t DAC_Align, uint16_t Data2, uint16_t Data1) +{ + uint32_t data = 0, tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_ALIGN(DAC_Align)); + assert_param(IS_DAC_DATA(Data1)); + assert_param(IS_DAC_DATA(Data2)); + + /* Calculate and set dual DAC data holding register value */ + if (DAC_Align == DAC_Align_8b_R) + { + data = ((uint32_t)Data2 << 8) | Data1; + } + else + { + data = ((uint32_t)Data2 << 16) | Data1; + } + + tmp = (uint32_t)DAC_BASE; + tmp += DHR12RD_OFFSET + DAC_Align; + + /* Set the dual DAC selected data holding register */ + *(__IO uint32_t *)tmp = data; +} + +/** + * @brief Returns the last data output value of the selected DAC channel. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @retval The selected DAC channel data output value. + */ +uint16_t DAC_GetDataOutputValue(uint32_t DAC_Channel) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + + tmp = (uint32_t) DAC_BASE ; + tmp += DOR_OFFSET + ((uint32_t)DAC_Channel >> 2); + + /* Returns the DAC channel data output register value */ + return (uint16_t) (*(__IO uint32_t*) tmp); +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) +/** + * @brief Checks whether the specified DAC flag is set or not. + * @param DAC_Channel: thee selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to check. + * This parameter can be only of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval The new state of DAC_FLAG (SET or RESET). + */ +FlagStatus DAC_GetFlagStatus(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Check the status of the specified DAC flag */ + if ((DAC->SR & (DAC_FLAG << DAC_Channel)) != (uint8_t)RESET) + { + /* DAC_FLAG is set */ + bitstatus = SET; + } + else + { + /* DAC_FLAG is reset */ + bitstatus = RESET; + } + /* Return the DAC_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx's pending flags. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_FLAG: specifies the flag to clear. + * This parameter can be of the following value: + * @arg DAC_FLAG_DMAUDR: DMA underrun flag + * @retval None + */ +void DAC_ClearFlag(uint32_t DAC_Channel, uint32_t DAC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_FLAG(DAC_FLAG)); + + /* Clear the selected DAC flags */ + DAC->SR = (DAC_FLAG << DAC_Channel); +} + +/** + * @brief Checks whether the specified DAC interrupt has occurred or not. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt source to check. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval The new state of DAC_IT (SET or RESET). + */ +ITStatus DAC_GetITStatus(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Get the DAC_IT enable bit status */ + enablestatus = (DAC->CR & (DAC_IT << DAC_Channel)) ; + + /* Check the status of the specified DAC interrupt */ + if (((DAC->SR & (DAC_IT << DAC_Channel)) != (uint32_t)RESET) && enablestatus) + { + /* DAC_IT is set */ + bitstatus = SET; + } + else + { + /* DAC_IT is reset */ + bitstatus = RESET; + } + /* Return the DAC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DAC channelx's interrupt pending bits. + * @param DAC_Channel: the selected DAC channel. + * This parameter can be one of the following values: + * @arg DAC_Channel_1: DAC Channel1 selected + * @arg DAC_Channel_2: DAC Channel2 selected + * @param DAC_IT: specifies the DAC interrupt pending bit to clear. + * This parameter can be the following values: + * @arg DAC_IT_DMAUDR: DMA underrun interrupt mask + * @retval None + */ +void DAC_ClearITPendingBit(uint32_t DAC_Channel, uint32_t DAC_IT) +{ + /* Check the parameters */ + assert_param(IS_DAC_CHANNEL(DAC_Channel)); + assert_param(IS_DAC_IT(DAC_IT)); + + /* Clear the selected DAC interrupt pending bits */ + DAC->SR = (DAC_IT << DAC_Channel); +} +#endif + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c new file mode 100755 index 0000000000..d34307b058 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dbgmcu.c @@ -0,0 +1,162 @@ +/** + ****************************************************************************** + * @file stm32f10x_dbgmcu.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DBGMCU firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dbgmcu.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DBGMCU + * @brief DBGMCU driver modules + * @{ + */ + +/** @defgroup DBGMCU_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Defines + * @{ + */ + +#define IDCODE_DEVID_MASK ((uint32_t)0x00000FFF) +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DBGMCU_Private_Functions + * @{ + */ + +/** + * @brief Returns the device revision identifier. + * @param None + * @retval Device revision identifier + */ +uint32_t DBGMCU_GetREVID(void) +{ + return(DBGMCU->IDCODE >> 16); +} + +/** + * @brief Returns the device identifier. + * @param None + * @retval Device identifier + */ +uint32_t DBGMCU_GetDEVID(void) +{ + return(DBGMCU->IDCODE & IDCODE_DEVID_MASK); +} + +/** + * @brief Configures the specified peripheral and low power mode behavior + * when the MCU under Debug mode. + * @param DBGMCU_Periph: specifies the peripheral and low power mode. + * This parameter can be any combination of the following values: + * @arg DBGMCU_SLEEP: Keep debugger connection during SLEEP mode + * @arg DBGMCU_STOP: Keep debugger connection during STOP mode + * @arg DBGMCU_STANDBY: Keep debugger connection during STANDBY mode + * @arg DBGMCU_IWDG_STOP: Debug IWDG stopped when Core is halted + * @arg DBGMCU_WWDG_STOP: Debug WWDG stopped when Core is halted + * @arg DBGMCU_TIM1_STOP: TIM1 counter stopped when Core is halted + * @arg DBGMCU_TIM2_STOP: TIM2 counter stopped when Core is halted + * @arg DBGMCU_TIM3_STOP: TIM3 counter stopped when Core is halted + * @arg DBGMCU_TIM4_STOP: TIM4 counter stopped when Core is halted + * @arg DBGMCU_CAN1_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_I2C1_SMBUS_TIMEOUT: I2C1 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_I2C2_SMBUS_TIMEOUT: I2C2 SMBUS timeout mode stopped when Core is halted + * @arg DBGMCU_TIM5_STOP: TIM5 counter stopped when Core is halted + * @arg DBGMCU_TIM6_STOP: TIM6 counter stopped when Core is halted + * @arg DBGMCU_TIM7_STOP: TIM7 counter stopped when Core is halted + * @arg DBGMCU_TIM8_STOP: TIM8 counter stopped when Core is halted + * @arg DBGMCU_CAN2_STOP: Debug CAN2 stopped when Core is halted + * @arg DBGMCU_TIM15_STOP: TIM15 counter stopped when Core is halted + * @arg DBGMCU_TIM16_STOP: TIM16 counter stopped when Core is halted + * @arg DBGMCU_TIM17_STOP: TIM17 counter stopped when Core is halted + * @arg DBGMCU_TIM9_STOP: TIM9 counter stopped when Core is halted + * @arg DBGMCU_TIM10_STOP: TIM10 counter stopped when Core is halted + * @arg DBGMCU_TIM11_STOP: TIM11 counter stopped when Core is halted + * @arg DBGMCU_TIM12_STOP: TIM12 counter stopped when Core is halted + * @arg DBGMCU_TIM13_STOP: TIM13 counter stopped when Core is halted + * @arg DBGMCU_TIM14_STOP: TIM14 counter stopped when Core is halted + * @param NewState: new state of the specified peripheral in Debug mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DBGMCU_Config(uint32_t DBGMCU_Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DBGMCU_PERIPH(DBGMCU_Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + DBGMCU->CR |= DBGMCU_Periph; + } + else + { + DBGMCU->CR &= ~DBGMCU_Periph; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c new file mode 100755 index 0000000000..0c86f9018b --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_dma.c @@ -0,0 +1,714 @@ +/** + ****************************************************************************** + * @file stm32f10x_dma.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the DMA firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_dma.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup DMA + * @brief DMA driver modules + * @{ + */ + +/** @defgroup DMA_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup DMA_Private_Defines + * @{ + */ + + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA1_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA1_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA1_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA1_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) +#define DMA1_Channel6_IT_Mask ((uint32_t)(DMA_ISR_GIF6 | DMA_ISR_TCIF6 | DMA_ISR_HTIF6 | DMA_ISR_TEIF6)) +#define DMA1_Channel7_IT_Mask ((uint32_t)(DMA_ISR_GIF7 | DMA_ISR_TCIF7 | DMA_ISR_HTIF7 | DMA_ISR_TEIF7)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_Channel1_IT_Mask ((uint32_t)(DMA_ISR_GIF1 | DMA_ISR_TCIF1 | DMA_ISR_HTIF1 | DMA_ISR_TEIF1)) +#define DMA2_Channel2_IT_Mask ((uint32_t)(DMA_ISR_GIF2 | DMA_ISR_TCIF2 | DMA_ISR_HTIF2 | DMA_ISR_TEIF2)) +#define DMA2_Channel3_IT_Mask ((uint32_t)(DMA_ISR_GIF3 | DMA_ISR_TCIF3 | DMA_ISR_HTIF3 | DMA_ISR_TEIF3)) +#define DMA2_Channel4_IT_Mask ((uint32_t)(DMA_ISR_GIF4 | DMA_ISR_TCIF4 | DMA_ISR_HTIF4 | DMA_ISR_TEIF4)) +#define DMA2_Channel5_IT_Mask ((uint32_t)(DMA_ISR_GIF5 | DMA_ISR_TCIF5 | DMA_ISR_HTIF5 | DMA_ISR_TEIF5)) + +/* DMA2 FLAG mask */ +#define FLAG_Mask ((uint32_t)0x10000000) + +/* DMA registers Masks */ +#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) + +/** + * @} + */ + +/** @defgroup DMA_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup DMA_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the DMAy Channelx registers to their default reset + * values. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval None + */ +void DMA_DeInit(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + + /* Reset DMAy Channelx control register */ + DMAy_Channelx->CCR = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAy_Channelx->CNDTR = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAy_Channelx->CPAR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAy_Channelx->CMAR = 0; + + if (DMAy_Channelx == DMA1_Channel1) + { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->IFCR |= DMA1_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel2) + { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->IFCR |= DMA1_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel3) + { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->IFCR |= DMA1_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel4) + { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->IFCR |= DMA1_Channel4_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel5) + { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->IFCR |= DMA1_Channel5_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel6) + { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->IFCR |= DMA1_Channel6_IT_Mask; + } + else if (DMAy_Channelx == DMA1_Channel7) + { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->IFCR |= DMA1_Channel7_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel1) + { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->IFCR |= DMA2_Channel1_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel2) + { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->IFCR |= DMA2_Channel2_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel3) + { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->IFCR |= DMA2_Channel3_IT_Mask; + } + else if (DMAy_Channelx == DMA2_Channel4) + { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->IFCR |= DMA2_Channel4_IT_Mask; + } + else + { + if (DMAy_Channelx == DMA2_Channel5) + { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->IFCR |= DMA2_Channel5_IT_Mask; + } + } +} + +/** + * @brief Initializes the DMAy Channelx according to the specified + * parameters in the DMA_InitStruct. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_InitStruct: pointer to a DMA_InitTypeDef structure that + * contains the configuration information for the specified DMA Channel. + * @retval None + */ +void DMA_Init(DMA_Channel_TypeDef* DMAy_Channelx, DMA_InitTypeDef* DMA_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_DIR(DMA_InitStruct->DMA_DIR)); + assert_param(IS_DMA_BUFFER_SIZE(DMA_InitStruct->DMA_BufferSize)); + assert_param(IS_DMA_PERIPHERAL_INC_STATE(DMA_InitStruct->DMA_PeripheralInc)); + assert_param(IS_DMA_MEMORY_INC_STATE(DMA_InitStruct->DMA_MemoryInc)); + assert_param(IS_DMA_PERIPHERAL_DATA_SIZE(DMA_InitStruct->DMA_PeripheralDataSize)); + assert_param(IS_DMA_MEMORY_DATA_SIZE(DMA_InitStruct->DMA_MemoryDataSize)); + assert_param(IS_DMA_MODE(DMA_InitStruct->DMA_Mode)); + assert_param(IS_DMA_PRIORITY(DMA_InitStruct->DMA_Priority)); + assert_param(IS_DMA_M2M_STATE(DMA_InitStruct->DMA_M2M)); + +/*--------------------------- DMAy Channelx CCR Configuration -----------------*/ + /* Get the DMAy_Channelx CCR value */ + tmpreg = DMAy_Channelx->CCR; + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpreg &= CCR_CLEAR_Mask; + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to DMA_DIR value */ + /* Set CIRC bit according to DMA_Mode value */ + /* Set PINC bit according to DMA_PeripheralInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to DMA_PeripheralDataSize value */ + /* Set MSIZE bits according to DMA_MemoryDataSize value */ + /* Set PL bits according to DMA_Priority value */ + /* Set the MEM2MEM bit according to DMA_M2M value */ + tmpreg |= DMA_InitStruct->DMA_DIR | DMA_InitStruct->DMA_Mode | + DMA_InitStruct->DMA_PeripheralInc | DMA_InitStruct->DMA_MemoryInc | + DMA_InitStruct->DMA_PeripheralDataSize | DMA_InitStruct->DMA_MemoryDataSize | + DMA_InitStruct->DMA_Priority | DMA_InitStruct->DMA_M2M; + + /* Write to DMAy Channelx CCR */ + DMAy_Channelx->CCR = tmpreg; + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DMA_InitStruct->DMA_BufferSize; + +/*--------------------------- DMAy Channelx CPAR Configuration ----------------*/ + /* Write to DMAy Channelx CPAR */ + DMAy_Channelx->CPAR = DMA_InitStruct->DMA_PeripheralBaseAddr; + +/*--------------------------- DMAy Channelx CMAR Configuration ----------------*/ + /* Write to DMAy Channelx CMAR */ + DMAy_Channelx->CMAR = DMA_InitStruct->DMA_MemoryBaseAddr; +} + +/** + * @brief Fills each DMA_InitStruct member with its default value. + * @param DMA_InitStruct : pointer to a DMA_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void DMA_StructInit(DMA_InitTypeDef* DMA_InitStruct) +{ +/*-------------- Reset DMA init structure parameters values ------------------*/ + /* Initialize the DMA_PeripheralBaseAddr member */ + DMA_InitStruct->DMA_PeripheralBaseAddr = 0; + /* Initialize the DMA_MemoryBaseAddr member */ + DMA_InitStruct->DMA_MemoryBaseAddr = 0; + /* Initialize the DMA_DIR member */ + DMA_InitStruct->DMA_DIR = DMA_DIR_PeripheralSRC; + /* Initialize the DMA_BufferSize member */ + DMA_InitStruct->DMA_BufferSize = 0; + /* Initialize the DMA_PeripheralInc member */ + DMA_InitStruct->DMA_PeripheralInc = DMA_PeripheralInc_Disable; + /* Initialize the DMA_MemoryInc member */ + DMA_InitStruct->DMA_MemoryInc = DMA_MemoryInc_Disable; + /* Initialize the DMA_PeripheralDataSize member */ + DMA_InitStruct->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + /* Initialize the DMA_MemoryDataSize member */ + DMA_InitStruct->DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + /* Initialize the DMA_Mode member */ + DMA_InitStruct->DMA_Mode = DMA_Mode_Normal; + /* Initialize the DMA_Priority member */ + DMA_InitStruct->DMA_Priority = DMA_Priority_Low; + /* Initialize the DMA_M2M member */ + DMA_InitStruct->DMA_M2M = DMA_M2M_Disable; +} + +/** + * @brief Enables or disables the specified DMAy Channelx. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param NewState: new state of the DMAy Channelx. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_Cmd(DMA_Channel_TypeDef* DMAy_Channelx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected DMAy Channelx */ + DMAy_Channelx->CCR |= DMA_CCR1_EN; + } + else + { + /* Disable the selected DMAy Channelx */ + DMAy_Channelx->CCR &= (uint16_t)(~DMA_CCR1_EN); + } +} + +/** + * @brief Enables or disables the specified DMAy Channelx interrupts. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DMA_IT: specifies the DMA interrupts sources to be enabled + * or disabled. + * This parameter can be any combination of the following values: + * @arg DMA_IT_TC: Transfer complete interrupt mask + * @arg DMA_IT_HT: Half transfer interrupt mask + * @arg DMA_IT_TE: Transfer error interrupt mask + * @param NewState: new state of the specified DMA interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void DMA_ITConfig(DMA_Channel_TypeDef* DMAy_Channelx, uint32_t DMA_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + assert_param(IS_DMA_CONFIG_IT(DMA_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected DMA interrupts */ + DMAy_Channelx->CCR |= DMA_IT; + } + else + { + /* Disable the selected DMA interrupts */ + DMAy_Channelx->CCR &= ~DMA_IT; + } +} + +/** + * @brief Sets the number of data units in the current DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @param DataNumber: The number of data units in the current DMAy Channelx + * transfer. + * @note This function can only be used when the DMAy_Channelx is disabled. + * @retval None. + */ +void DMA_SetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx, uint16_t DataNumber) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + +/*--------------------------- DMAy Channelx CNDTR Configuration ---------------*/ + /* Write to DMAy Channelx CNDTR */ + DMAy_Channelx->CNDTR = DataNumber; +} + +/** + * @brief Returns the number of remaining data units in the current + * DMAy Channelx transfer. + * @param DMAy_Channelx: where y can be 1 or 2 to select the DMA and + * x can be 1 to 7 for DMA1 and 1 to 5 for DMA2 to select the DMA Channel. + * @retval The number of remaining data units in the current DMAy Channelx + * transfer. + */ +uint16_t DMA_GetCurrDataCounter(DMA_Channel_TypeDef* DMAy_Channelx) +{ + /* Check the parameters */ + assert_param(IS_DMA_ALL_PERIPH(DMAy_Channelx)); + /* Return the number of remaining data units for DMAy Channelx */ + return ((uint16_t)(DMAy_Channelx->CNDTR)); +} + +/** + * @brief Checks whether the specified DMAy Channelx flag is set or not. + * @param DMAy_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval The new state of DMAy_FLAG (SET or RESET). + */ +FlagStatus DMA_GetFlagStatus(uint32_t DMAy_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_FLAG(DMAy_FLAG)); + + /* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR ; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR ; + } + + /* Check the status of the specified DMAy flag */ + if ((tmpreg & DMAy_FLAG) != (uint32_t)RESET) + { + /* DMAy_FLAG is set */ + bitstatus = SET; + } + else + { + /* DMAy_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the DMAy_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's pending flags. + * @param DMAy_FLAG: specifies the flag to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_FLAG_GL1: DMA1 Channel1 global flag. + * @arg DMA1_FLAG_TC1: DMA1 Channel1 transfer complete flag. + * @arg DMA1_FLAG_HT1: DMA1 Channel1 half transfer flag. + * @arg DMA1_FLAG_TE1: DMA1 Channel1 transfer error flag. + * @arg DMA1_FLAG_GL2: DMA1 Channel2 global flag. + * @arg DMA1_FLAG_TC2: DMA1 Channel2 transfer complete flag. + * @arg DMA1_FLAG_HT2: DMA1 Channel2 half transfer flag. + * @arg DMA1_FLAG_TE2: DMA1 Channel2 transfer error flag. + * @arg DMA1_FLAG_GL3: DMA1 Channel3 global flag. + * @arg DMA1_FLAG_TC3: DMA1 Channel3 transfer complete flag. + * @arg DMA1_FLAG_HT3: DMA1 Channel3 half transfer flag. + * @arg DMA1_FLAG_TE3: DMA1 Channel3 transfer error flag. + * @arg DMA1_FLAG_GL4: DMA1 Channel4 global flag. + * @arg DMA1_FLAG_TC4: DMA1 Channel4 transfer complete flag. + * @arg DMA1_FLAG_HT4: DMA1 Channel4 half transfer flag. + * @arg DMA1_FLAG_TE4: DMA1 Channel4 transfer error flag. + * @arg DMA1_FLAG_GL5: DMA1 Channel5 global flag. + * @arg DMA1_FLAG_TC5: DMA1 Channel5 transfer complete flag. + * @arg DMA1_FLAG_HT5: DMA1 Channel5 half transfer flag. + * @arg DMA1_FLAG_TE5: DMA1 Channel5 transfer error flag. + * @arg DMA1_FLAG_GL6: DMA1 Channel6 global flag. + * @arg DMA1_FLAG_TC6: DMA1 Channel6 transfer complete flag. + * @arg DMA1_FLAG_HT6: DMA1 Channel6 half transfer flag. + * @arg DMA1_FLAG_TE6: DMA1 Channel6 transfer error flag. + * @arg DMA1_FLAG_GL7: DMA1 Channel7 global flag. + * @arg DMA1_FLAG_TC7: DMA1 Channel7 transfer complete flag. + * @arg DMA1_FLAG_HT7: DMA1 Channel7 half transfer flag. + * @arg DMA1_FLAG_TE7: DMA1 Channel7 transfer error flag. + * @arg DMA2_FLAG_GL1: DMA2 Channel1 global flag. + * @arg DMA2_FLAG_TC1: DMA2 Channel1 transfer complete flag. + * @arg DMA2_FLAG_HT1: DMA2 Channel1 half transfer flag. + * @arg DMA2_FLAG_TE1: DMA2 Channel1 transfer error flag. + * @arg DMA2_FLAG_GL2: DMA2 Channel2 global flag. + * @arg DMA2_FLAG_TC2: DMA2 Channel2 transfer complete flag. + * @arg DMA2_FLAG_HT2: DMA2 Channel2 half transfer flag. + * @arg DMA2_FLAG_TE2: DMA2 Channel2 transfer error flag. + * @arg DMA2_FLAG_GL3: DMA2 Channel3 global flag. + * @arg DMA2_FLAG_TC3: DMA2 Channel3 transfer complete flag. + * @arg DMA2_FLAG_HT3: DMA2 Channel3 half transfer flag. + * @arg DMA2_FLAG_TE3: DMA2 Channel3 transfer error flag. + * @arg DMA2_FLAG_GL4: DMA2 Channel4 global flag. + * @arg DMA2_FLAG_TC4: DMA2 Channel4 transfer complete flag. + * @arg DMA2_FLAG_HT4: DMA2 Channel4 half transfer flag. + * @arg DMA2_FLAG_TE4: DMA2 Channel4 transfer error flag. + * @arg DMA2_FLAG_GL5: DMA2 Channel5 global flag. + * @arg DMA2_FLAG_TC5: DMA2 Channel5 transfer complete flag. + * @arg DMA2_FLAG_HT5: DMA2 Channel5 half transfer flag. + * @arg DMA2_FLAG_TE5: DMA2 Channel5 transfer error flag. + * @retval None + */ +void DMA_ClearFlag(uint32_t DMAy_FLAG) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_FLAG(DMAy_FLAG)); + + /* Calculate the used DMAy */ + if ((DMAy_FLAG & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy flags */ + DMA2->IFCR = DMAy_FLAG; + } + else + { + /* Clear the selected DMAy flags */ + DMA1->IFCR = DMAy_FLAG; + } +} + +/** + * @brief Checks whether the specified DMAy Channelx interrupt has occurred or not. + * @param DMAy_IT: specifies the DMAy interrupt source to check. + * This parameter can be one of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval The new state of DMAy_IT (SET or RESET). + */ +ITStatus DMA_GetITStatus(uint32_t DMAy_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_DMA_GET_IT(DMAy_IT)); + + /* Calculate the used DMA */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Get DMA2 ISR register value */ + tmpreg = DMA2->ISR; + } + else + { + /* Get DMA1 ISR register value */ + tmpreg = DMA1->ISR; + } + + /* Check the status of the specified DMAy interrupt */ + if ((tmpreg & DMAy_IT) != (uint32_t)RESET) + { + /* DMAy_IT is set */ + bitstatus = SET; + } + else + { + /* DMAy_IT is reset */ + bitstatus = RESET; + } + /* Return the DMA_IT status */ + return bitstatus; +} + +/** + * @brief Clears the DMAy Channelx's interrupt pending bits. + * @param DMAy_IT: specifies the DMAy interrupt pending bit to clear. + * This parameter can be any combination (for the same DMA) of the following values: + * @arg DMA1_IT_GL1: DMA1 Channel1 global interrupt. + * @arg DMA1_IT_TC1: DMA1 Channel1 transfer complete interrupt. + * @arg DMA1_IT_HT1: DMA1 Channel1 half transfer interrupt. + * @arg DMA1_IT_TE1: DMA1 Channel1 transfer error interrupt. + * @arg DMA1_IT_GL2: DMA1 Channel2 global interrupt. + * @arg DMA1_IT_TC2: DMA1 Channel2 transfer complete interrupt. + * @arg DMA1_IT_HT2: DMA1 Channel2 half transfer interrupt. + * @arg DMA1_IT_TE2: DMA1 Channel2 transfer error interrupt. + * @arg DMA1_IT_GL3: DMA1 Channel3 global interrupt. + * @arg DMA1_IT_TC3: DMA1 Channel3 transfer complete interrupt. + * @arg DMA1_IT_HT3: DMA1 Channel3 half transfer interrupt. + * @arg DMA1_IT_TE3: DMA1 Channel3 transfer error interrupt. + * @arg DMA1_IT_GL4: DMA1 Channel4 global interrupt. + * @arg DMA1_IT_TC4: DMA1 Channel4 transfer complete interrupt. + * @arg DMA1_IT_HT4: DMA1 Channel4 half transfer interrupt. + * @arg DMA1_IT_TE4: DMA1 Channel4 transfer error interrupt. + * @arg DMA1_IT_GL5: DMA1 Channel5 global interrupt. + * @arg DMA1_IT_TC5: DMA1 Channel5 transfer complete interrupt. + * @arg DMA1_IT_HT5: DMA1 Channel5 half transfer interrupt. + * @arg DMA1_IT_TE5: DMA1 Channel5 transfer error interrupt. + * @arg DMA1_IT_GL6: DMA1 Channel6 global interrupt. + * @arg DMA1_IT_TC6: DMA1 Channel6 transfer complete interrupt. + * @arg DMA1_IT_HT6: DMA1 Channel6 half transfer interrupt. + * @arg DMA1_IT_TE6: DMA1 Channel6 transfer error interrupt. + * @arg DMA1_IT_GL7: DMA1 Channel7 global interrupt. + * @arg DMA1_IT_TC7: DMA1 Channel7 transfer complete interrupt. + * @arg DMA1_IT_HT7: DMA1 Channel7 half transfer interrupt. + * @arg DMA1_IT_TE7: DMA1 Channel7 transfer error interrupt. + * @arg DMA2_IT_GL1: DMA2 Channel1 global interrupt. + * @arg DMA2_IT_TC1: DMA2 Channel1 transfer complete interrupt. + * @arg DMA2_IT_HT1: DMA2 Channel1 half transfer interrupt. + * @arg DMA2_IT_TE1: DMA2 Channel1 transfer error interrupt. + * @arg DMA2_IT_GL2: DMA2 Channel2 global interrupt. + * @arg DMA2_IT_TC2: DMA2 Channel2 transfer complete interrupt. + * @arg DMA2_IT_HT2: DMA2 Channel2 half transfer interrupt. + * @arg DMA2_IT_TE2: DMA2 Channel2 transfer error interrupt. + * @arg DMA2_IT_GL3: DMA2 Channel3 global interrupt. + * @arg DMA2_IT_TC3: DMA2 Channel3 transfer complete interrupt. + * @arg DMA2_IT_HT3: DMA2 Channel3 half transfer interrupt. + * @arg DMA2_IT_TE3: DMA2 Channel3 transfer error interrupt. + * @arg DMA2_IT_GL4: DMA2 Channel4 global interrupt. + * @arg DMA2_IT_TC4: DMA2 Channel4 transfer complete interrupt. + * @arg DMA2_IT_HT4: DMA2 Channel4 half transfer interrupt. + * @arg DMA2_IT_TE4: DMA2 Channel4 transfer error interrupt. + * @arg DMA2_IT_GL5: DMA2 Channel5 global interrupt. + * @arg DMA2_IT_TC5: DMA2 Channel5 transfer complete interrupt. + * @arg DMA2_IT_HT5: DMA2 Channel5 half transfer interrupt. + * @arg DMA2_IT_TE5: DMA2 Channel5 transfer error interrupt. + * @retval None + */ +void DMA_ClearITPendingBit(uint32_t DMAy_IT) +{ + /* Check the parameters */ + assert_param(IS_DMA_CLEAR_IT(DMAy_IT)); + + /* Calculate the used DMAy */ + if ((DMAy_IT & FLAG_Mask) != (uint32_t)RESET) + { + /* Clear the selected DMAy interrupt pending bits */ + DMA2->IFCR = DMAy_IT; + } + else + { + /* Clear the selected DMAy interrupt pending bits */ + DMA1->IFCR = DMAy_IT; + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c new file mode 100755 index 0000000000..ab7346276c --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_exti.c @@ -0,0 +1,269 @@ +/** + ****************************************************************************** + * @file stm32f10x_exti.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the EXTI firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_exti.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup EXTI + * @brief EXTI driver modules + * @{ + */ + +/** @defgroup EXTI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Defines + * @{ + */ + +#define EXTI_LINENONE ((uint32_t)0x00000) /* No interrupt selected */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup EXTI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the EXTI peripheral registers to their default reset values. + * @param None + * @retval None + */ +void EXTI_DeInit(void) +{ + EXTI->IMR = 0x00000000; + EXTI->EMR = 0x00000000; + EXTI->RTSR = 0x00000000; + EXTI->FTSR = 0x00000000; + EXTI->PR = 0x000FFFFF; +} + +/** + * @brief Initializes the EXTI peripheral according to the specified + * parameters in the EXTI_InitStruct. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure + * that contains the configuration information for the EXTI peripheral. + * @retval None + */ +void EXTI_Init(EXTI_InitTypeDef* EXTI_InitStruct) +{ + uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_EXTI_MODE(EXTI_InitStruct->EXTI_Mode)); + assert_param(IS_EXTI_TRIGGER(EXTI_InitStruct->EXTI_Trigger)); + assert_param(IS_EXTI_LINE(EXTI_InitStruct->EXTI_Line)); + assert_param(IS_FUNCTIONAL_STATE(EXTI_InitStruct->EXTI_LineCmd)); + + tmp = (uint32_t)EXTI_BASE; + + if (EXTI_InitStruct->EXTI_LineCmd != DISABLE) + { + /* Clear EXTI line configuration */ + EXTI->IMR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->EMR &= ~EXTI_InitStruct->EXTI_Line; + + tmp += EXTI_InitStruct->EXTI_Mode; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + + /* Clear Rising Falling edge configuration */ + EXTI->RTSR &= ~EXTI_InitStruct->EXTI_Line; + EXTI->FTSR &= ~EXTI_InitStruct->EXTI_Line; + + /* Select the trigger for the selected external interrupts */ + if (EXTI_InitStruct->EXTI_Trigger == EXTI_Trigger_Rising_Falling) + { + /* Rising Falling edge */ + EXTI->RTSR |= EXTI_InitStruct->EXTI_Line; + EXTI->FTSR |= EXTI_InitStruct->EXTI_Line; + } + else + { + tmp = (uint32_t)EXTI_BASE; + tmp += EXTI_InitStruct->EXTI_Trigger; + + *(__IO uint32_t *) tmp |= EXTI_InitStruct->EXTI_Line; + } + } + else + { + tmp += EXTI_InitStruct->EXTI_Mode; + + /* Disable the selected external lines */ + *(__IO uint32_t *) tmp &= ~EXTI_InitStruct->EXTI_Line; + } +} + +/** + * @brief Fills each EXTI_InitStruct member with its reset value. + * @param EXTI_InitStruct: pointer to a EXTI_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void EXTI_StructInit(EXTI_InitTypeDef* EXTI_InitStruct) +{ + EXTI_InitStruct->EXTI_Line = EXTI_LINENONE; + EXTI_InitStruct->EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStruct->EXTI_Trigger = EXTI_Trigger_Falling; + EXTI_InitStruct->EXTI_LineCmd = DISABLE; +} + +/** + * @brief Generates a Software interrupt. + * @param EXTI_Line: specifies the EXTI lines to be enabled or disabled. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_GenerateSWInterrupt(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->SWIER |= EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line flag is set or not. + * @param EXTI_Line: specifies the EXTI line flag to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +FlagStatus EXTI_GetFlagStatus(uint32_t EXTI_Line) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + if ((EXTI->PR & EXTI_Line) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending flags. + * @param EXTI_Line: specifies the EXTI lines flags to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearFlag(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @brief Checks whether the specified EXTI line is asserted or not. + * @param EXTI_Line: specifies the EXTI line to check. + * This parameter can be: + * @arg EXTI_Linex: External interrupt line x where x(0..19) + * @retval The new state of EXTI_Line (SET or RESET). + */ +ITStatus EXTI_GetITStatus(uint32_t EXTI_Line) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + /* Check the parameters */ + assert_param(IS_GET_EXTI_LINE(EXTI_Line)); + + enablestatus = EXTI->IMR & EXTI_Line; + if (((EXTI->PR & EXTI_Line) != (uint32_t)RESET) && (enablestatus != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the EXTI's line pending bits. + * @param EXTI_Line: specifies the EXTI lines to clear. + * This parameter can be any combination of EXTI_Linex where x can be (0..19). + * @retval None + */ +void EXTI_ClearITPendingBit(uint32_t EXTI_Line) +{ + /* Check the parameters */ + assert_param(IS_EXTI_LINE(EXTI_Line)); + + EXTI->PR = EXTI_Line; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c new file mode 100755 index 0000000000..f6c7bf172d --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_flash.c @@ -0,0 +1,1684 @@ +/** + ****************************************************************************** + * @file stm32f10x_flash.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the FLASH firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_flash.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FLASH + * @brief FLASH driver modules + * @{ + */ + +/** @defgroup FLASH_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Defines + * @{ + */ + +/* Flash Access Control Register bits */ +#define ACR_LATENCY_Mask ((uint32_t)0x00000038) +#define ACR_HLFCYA_Mask ((uint32_t)0xFFFFFFF7) +#define ACR_PRFTBE_Mask ((uint32_t)0xFFFFFFEF) + +/* Flash Access Control Register bits */ +#define ACR_PRFTBS_Mask ((uint32_t)0x00000020) + +/* Flash Control Register bits */ +#define CR_PG_Set ((uint32_t)0x00000001) +#define CR_PG_Reset ((uint32_t)0x00001FFE) +#define CR_PER_Set ((uint32_t)0x00000002) +#define CR_PER_Reset ((uint32_t)0x00001FFD) +#define CR_MER_Set ((uint32_t)0x00000004) +#define CR_MER_Reset ((uint32_t)0x00001FFB) +#define CR_OPTPG_Set ((uint32_t)0x00000010) +#define CR_OPTPG_Reset ((uint32_t)0x00001FEF) +#define CR_OPTER_Set ((uint32_t)0x00000020) +#define CR_OPTER_Reset ((uint32_t)0x00001FDF) +#define CR_STRT_Set ((uint32_t)0x00000040) +#define CR_LOCK_Set ((uint32_t)0x00000080) + +/* FLASH Mask */ +#define RDPRT_Mask ((uint32_t)0x00000002) +#define WRP0_Mask ((uint32_t)0x000000FF) +#define WRP1_Mask ((uint32_t)0x0000FF00) +#define WRP2_Mask ((uint32_t)0x00FF0000) +#define WRP3_Mask ((uint32_t)0xFF000000) +#define OB_USER_BFB2 ((uint16_t)0x0008) + +/* FLASH Keys */ +#define RDP_Key ((uint16_t)0x00A5) +#define FLASH_KEY1 ((uint32_t)0x45670123) +#define FLASH_KEY2 ((uint32_t)0xCDEF89AB) + +/* FLASH BANK address */ +#define FLASH_BANK1_END_ADDRESS ((uint32_t)0x807FFFF) + +/* Delay definition */ +#define EraseTimeout ((uint32_t)0x000B0000) +#define ProgramTimeout ((uint32_t)0x00002000) +/** + * @} + */ + +/** @defgroup FLASH_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FLASH_Private_Functions + * @{ + */ + +/** +@code + + This driver provides functions to configure and program the Flash memory of all STM32F10x devices, + including the latest STM32F10x_XL density devices. + + STM32F10x_XL devices feature up to 1 Mbyte with dual bank architecture for read-while-write (RWW) capability: + - bank1: fixed size of 512 Kbytes (256 pages of 2Kbytes each) + - bank2: up to 512 Kbytes (up to 256 pages of 2Kbytes each) + While other STM32F10x devices features only one bank with memory up to 512 Kbytes. + + In version V3.3.0, some functions were updated and new ones were added to support + STM32F10x_XL devices. Thus some functions manages all devices, while other are + dedicated for XL devices only. + + The table below presents the list of available functions depending on the used STM32F10x devices. + + *************************************************** + * Legacy functions used for all STM32F10x devices * + *************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_SetLatency | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_HalfCycleAccessCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_PrefetchBufferCmd | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Unlock | Yes | Yes | - For STM32F10X_XL devices: unlock Bank1 and Bank2. | + | | | | - For other devices: unlock Bank1 and it is equivalent | + | | | | to FLASH_UnlockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_Lock | Yes | Yes | - For STM32F10X_XL devices: lock Bank1 and Bank2. | + | | | | - For other devices: lock Bank1 and it is equivalent | + | | | | to FLASH_LockBank1 function. | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ErasePage | Yes | Yes | - For STM32F10x_XL devices: erase a page in Bank1 and Bank2 | + | | | | - For other devices: erase a page in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseAllPages | Yes | Yes | - For STM32F10x_XL devices: erase all pages in Bank1 and Bank2 | + | | | | - For other devices: erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EraseOptionBytes | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramHalfWord | Yes | Yes | Updated to program up to 1MByte (depending on the used device) | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ProgramOptionByteData | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_EnableWriteProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ReadOutProtection | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_UserOptionByteConfig | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetUserOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetWriteProtectionOptionByte | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetReadOutProtectionStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetPrefetchBufferStatus | Yes | Yes | No change | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ITConfig | Yes | Yes | - For STM32F10x_XL devices: enable Bank1 and Bank2's interrupts| + | | | | - For other devices: enable Bank1's interrupts | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetFlagStatus | Yes | Yes | - For STM32F10x_XL devices: return Bank1 and Bank2's flag status| + | | | | - For other devices: return Bank1's flag status | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_ClearFlag | Yes | Yes | - For STM32F10x_XL devices: clear Bank1 and Bank2's flag | + | | | | - For other devices: clear Bank1's flag | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_GetStatus | Yes | Yes | - Return the status of Bank1 (for all devices) | + | | | | equivalent to FLASH_GetBank1Status function | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_WaitForLastOperation | Yes | Yes | - Wait for Bank1 last operation (for all devices) | + | | | | equivalent to: FLASH_WaitForLastBank1Operation function | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ************************************************************************************************************************ + * New functions used for all STM32F10x devices to manage Bank1: * + * - These functions are mainly useful for STM32F10x_XL density devices, to have separate control for Bank1 and bank2 * + * - For other devices, these functions are optional (covered by functions listed above) * + ************************************************************************************************************************ + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank1 | Yes | Yes | - Unlock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank1 | Yes | Yes | - Lock Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank1Pages | Yes | Yes | - Erase all pages in Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank1Status | Yes | Yes | - Return the status of Bank1 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank1Operation | Yes | Yes | - Wait for Bank1 last operation | + +----------------------------------------------------------------------------------------------------------------------------------+ + + ***************************************************************************** + * New Functions used only with STM32F10x_XL density devices to manage Bank2 * + ***************************************************************************** + +----------------------------------------------------------------------------------------------------------------------------------+ + | Functions prototypes |STM32F10x_XL|Other STM32F10x| Comments | + | | devices | devices | | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_UnlockBank2 | Yes | No | - Unlock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + |FLASH_LockBank2 | Yes | No | - Lock Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_EraseAllBank2Pages | Yes | No | - Erase all pages in Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_GetBank2Status | Yes | No | - Return the status of Bank2 | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_WaitForLastBank2Operation | Yes | No | - Wait for Bank2 last operation | + |----------------------------------------------------------------------------------------------------------------------------------| + | FLASH_BootConfig | Yes | No | - Configure to boot from Bank1 or Bank2 | + +----------------------------------------------------------------------------------------------------------------------------------+ +@endcode +*/ + + +/** + * @brief Sets the code latency value. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Latency: specifies the FLASH Latency value. + * This parameter can be one of the following values: + * @arg FLASH_Latency_0: FLASH Zero Latency cycle + * @arg FLASH_Latency_1: FLASH One Latency cycle + * @arg FLASH_Latency_2: FLASH Two Latency cycles + * @retval None + */ +void FLASH_SetLatency(uint32_t FLASH_Latency) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_LATENCY(FLASH_Latency)); + + /* Read the ACR register */ + tmpreg = FLASH->ACR; + + /* Sets the Latency value */ + tmpreg &= ACR_LATENCY_Mask; + tmpreg |= FLASH_Latency; + + /* Write the ACR register */ + FLASH->ACR = tmpreg; +} + +/** + * @brief Enables or disables the Half cycle flash access. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_HalfCycleAccess: specifies the FLASH Half cycle Access mode. + * This parameter can be one of the following values: + * @arg FLASH_HalfCycleAccess_Enable: FLASH Half Cycle Enable + * @arg FLASH_HalfCycleAccess_Disable: FLASH Half Cycle Disable + * @retval None + */ +void FLASH_HalfCycleAccessCmd(uint32_t FLASH_HalfCycleAccess) +{ + /* Check the parameters */ + assert_param(IS_FLASH_HALFCYCLEACCESS_STATE(FLASH_HalfCycleAccess)); + + /* Enable or disable the Half cycle access */ + FLASH->ACR &= ACR_HLFCYA_Mask; + FLASH->ACR |= FLASH_HalfCycleAccess; +} + +/** + * @brief Enables or disables the Prefetch Buffer. + * @note This function can be used for all STM32F10x devices. + * @param FLASH_PrefetchBuffer: specifies the Prefetch buffer status. + * This parameter can be one of the following values: + * @arg FLASH_PrefetchBuffer_Enable: FLASH Prefetch Buffer Enable + * @arg FLASH_PrefetchBuffer_Disable: FLASH Prefetch Buffer Disable + * @retval None + */ +void FLASH_PrefetchBufferCmd(uint32_t FLASH_PrefetchBuffer) +{ + /* Check the parameters */ + assert_param(IS_FLASH_PREFETCHBUFFER_STATE(FLASH_PrefetchBuffer)); + + /* Enable or disable the Prefetch Buffer */ + FLASH->ACR &= ACR_PRFTBE_Mask; + FLASH->ACR |= FLASH_PrefetchBuffer; +} + +/** + * @brief Unlocks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1 and Bank2. + * - For all other devices it unlocks Bank1 and it is equivalent + * to FLASH_UnlockBank1 function.. + * @param None + * @retval None + */ +void FLASH_Unlock(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; + +#ifdef STM32F10X_XL + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; +#endif /* STM32F10X_XL */ +} +/** + * @brief Unlocks the FLASH Bank1 Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function unlocks Bank1. + * - For all other devices it unlocks Bank1 and it is + * equivalent to FLASH_Unlock function. + * @param None + * @retval None + */ +void FLASH_UnlockBank1(void) +{ + /* Authorize the FPEC of Bank1 Access */ + FLASH->KEYR = FLASH_KEY1; + FLASH->KEYR = FLASH_KEY2; +} + +#ifdef STM32F10X_XL +/** + * @brief Unlocks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_UnlockBank2(void) +{ + /* Authorize the FPEC of Bank2 Access */ + FLASH->KEYR2 = FLASH_KEY1; + FLASH->KEYR2 = FLASH_KEY2; + +} +#endif /* STM32F10X_XL */ + +/** + * @brief Locks the FLASH Program Erase Controller. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1 and Bank2. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_LockBank1 function. + * @param None + * @retval None + */ +void FLASH_Lock(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; + +#ifdef STM32F10X_XL + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Locks the FLASH Bank1 Program Erase Controller. + * @note this function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function Locks Bank1. + * - For all other devices it Locks Bank1 and it is equivalent + * to FLASH_Lock function. + * @param None + * @retval None + */ +void FLASH_LockBank1(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank1 */ + FLASH->CR |= CR_LOCK_Set; +} + +#ifdef STM32F10X_XL +/** + * @brief Locks the FLASH Bank2 Program Erase Controller. + * @note This function can be used only for STM32F10X_XL density devices. + * @param None + * @retval None + */ +void FLASH_LockBank2(void) +{ + /* Set the Lock Bit to lock the FPEC and the CR of Bank2 */ + FLASH->CR2 |= CR_LOCK_Set; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases a specified FLASH page. + * @note This function can be used for all STM32F10x devices. + * @param Page_Address: The page address to be erased. + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ErasePage(uint32_t Page_Address) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Page_Address)); + +#ifdef STM32F10X_XL + if(Page_Address < FLASH_BANK1_END_ADDRESS) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR2|= CR_PER_Set; + FLASH->AR2 = Page_Address; + FLASH->CR2|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR2 &= CR_PER_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase the page */ + FLASH->CR|= CR_PER_Set; + FLASH->AR = Page_Address; + FLASH->CR|= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the PER Bit */ + FLASH->CR &= CR_PER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all FLASH pages. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllPages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Erase Status */ + return status; +} + +/** + * @brief Erases all Bank1 FLASH pages. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices this function erases all Bank1 pages. + * - For all other devices it erases all Bank1 pages and it is equivalent + * to FLASH_EraseAllPages function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank1Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR |= CR_MER_Set; + FLASH->CR |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Erases all Bank2 FLASH pages. + * @note This function can be used only for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseAllBank2Pages(void) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to erase all pages */ + FLASH->CR2 |= CR_MER_Set; + FLASH->CR2 |= CR_STRT_Set; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(EraseTimeout); + + /* Disable the MER Bit */ + FLASH->CR2 &= CR_MER_Reset; + } + /* Return the Erase Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Erases the FLASH option bytes. + * @note This functions erases all option bytes except the Read protection (RDP). + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EraseOptionBytes(void) +{ + uint16_t rdptmp = RDP_Key; + + FLASH_Status status = FLASH_COMPLETE; + + /* Get the actual read protection Option Byte value */ + if(FLASH_GetReadOutProtectionStatus() != RESET) + { + rdptmp = 0x00; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* if the previous operation is completed, proceed to erase the option bytes */ + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + /* Restore the last read protection Option Byte value */ + OB->RDP = (uint16_t)rdptmp; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if (status != FLASH_TIMEOUT) + { + /* Disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + } + /* Return the erase status */ + return status; +} + +/** + * @brief Programs a word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramWord(uint32_t Address, uint32_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + if(Address < FLASH_BANK1_END_ADDRESS - 2) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + } + else if(Address == (FLASH_BANK1_END_ADDRESS - 1)) + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + FLASH->CR2 |= CR_PG_Set; + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + else + { + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new first + half word */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = (uint16_t)Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new second + half word */ + tmp = Address + 2; + + *(__IO uint16_t*) tmp = Data >> 16; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + else + { + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramHalfWord(uint32_t Address, uint16_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FLASH_ADDRESS(Address)); + +#ifdef STM32F10X_XL + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(Address < FLASH_BANK1_END_ADDRESS) + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank1Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } + } + else + { + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR2 |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastBank2Operation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR2 &= CR_PG_Reset; + } + } +#else + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* if the previous operation is completed, proceed to program the new data */ + FLASH->CR |= CR_PG_Set; + + *(__IO uint16_t*)Address = Data; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + /* Disable the PG Bit */ + FLASH->CR &= CR_PG_Reset; + } +#endif /* STM32F10X_XL */ + + /* Return the Program Status */ + return status; +} + +/** + * @brief Programs a half word at a specified Option Byte Data address. + * @note This function can be used for all STM32F10x devices. + * @param Address: specifies the address to be programmed. + * This parameter can be 0x1FFFF804 or 0x1FFFF806. + * @param Data: specifies the data to be programmed. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ProgramOptionByteData(uint32_t Address, uint8_t Data) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_OB_DATA_ADDRESS(Address)); + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + /* Enables the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + *(__IO uint16_t*)Address = Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte Data Program Status */ + return status; +} + +/** + * @brief Write protects the desired pages + * @note This function can be used for all STM32F10x devices. + * @param FLASH_Pages: specifies the address of the pages to be write protected. + * This parameter can be: + * @arg For @b STM32_Low-density_devices: value between FLASH_WRProt_Pages0to3 and FLASH_WRProt_Pages28to31 + * @arg For @b STM32_Medium-density_devices: value between FLASH_WRProt_Pages0to3 + * and FLASH_WRProt_Pages124to127 + * @arg For @b STM32_High-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to255 + * @arg For @b STM32_Connectivity_line_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to127 + * @arg For @b STM32_XL-density_devices: value between FLASH_WRProt_Pages0to1 and + * FLASH_WRProt_Pages60to61 or FLASH_WRProt_Pages62to511 + * @arg FLASH_WRProt_AllPages + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_EnableWriteProtection(uint32_t FLASH_Pages) +{ + uint16_t WRP0_Data = 0xFFFF, WRP1_Data = 0xFFFF, WRP2_Data = 0xFFFF, WRP3_Data = 0xFFFF; + + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_FLASH_WRPROT_PAGE(FLASH_Pages)); + + FLASH_Pages = (uint32_t)(~FLASH_Pages); + WRP0_Data = (uint16_t)(FLASH_Pages & WRP0_Mask); + WRP1_Data = (uint16_t)((FLASH_Pages & WRP1_Mask) >> 8); + WRP2_Data = (uint16_t)((FLASH_Pages & WRP2_Mask) >> 16); + WRP3_Data = (uint16_t)((FLASH_Pages & WRP3_Mask) >> 24); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTPG_Set; + if(WRP0_Data != 0xFF) + { + OB->WRP0 = WRP0_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP1_Data != 0xFF)) + { + OB->WRP1 = WRP1_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + if((status == FLASH_COMPLETE) && (WRP2_Data != 0xFF)) + { + OB->WRP2 = WRP2_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if((status == FLASH_COMPLETE)&& (WRP3_Data != 0xFF)) + { + OB->WRP3 = WRP3_Data; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + } + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the write protection operation Status */ + return status; +} + +/** + * @brief Enables or disables the read out protection. + * @note If the user has already programmed the other option bytes before calling + * this function, he must re-program them since this function erases all option bytes. + * @note This function can be used for all STM32F10x devices. + * @param Newstate: new state of the ReadOut Protection. + * This parameter can be: ENABLE or DISABLE. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_ReadOutProtection(FunctionalState NewState) +{ + FLASH_Status status = FLASH_COMPLETE; + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* Authorizes the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + FLASH->CR |= CR_OPTER_Set; + FLASH->CR |= CR_STRT_Set; + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + if(status == FLASH_COMPLETE) + { + /* if the erase operation is completed, disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + if(NewState != DISABLE) + { + OB->RDP = 0x00; + } + else + { + OB->RDP = RDP_Key; + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(EraseTimeout); + + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + else + { + if(status != FLASH_TIMEOUT) + { + /* Disable the OPTER Bit */ + FLASH->CR &= CR_OPTER_Reset; + } + } + } + /* Return the protection operation Status */ + return status; +} + +/** + * @brief Programs the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. + * @note This function can be used for all STM32F10x devices. + * @param OB_IWDG: Selects the IWDG mode + * This parameter can be one of the following values: + * @arg OB_IWDG_SW: Software IWDG selected + * @arg OB_IWDG_HW: Hardware IWDG selected + * @param OB_STOP: Reset event when entering STOP mode. + * This parameter can be one of the following values: + * @arg OB_STOP_NoRST: No reset generated when entering in STOP + * @arg OB_STOP_RST: Reset generated when entering in STOP + * @param OB_STDBY: Reset event when entering Standby mode. + * This parameter can be one of the following values: + * @arg OB_STDBY_NoRST: No reset generated when entering in STANDBY + * @arg OB_STDBY_RST: Reset generated when entering in STANDBY + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_UserOptionByteConfig(uint16_t OB_IWDG, uint16_t OB_STOP, uint16_t OB_STDBY) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check the parameters */ + assert_param(IS_OB_IWDG_SOURCE(OB_IWDG)); + assert_param(IS_OB_STOP_SOURCE(OB_STOP)); + assert_param(IS_OB_STDBY_SOURCE(OB_STDBY)); + + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + OB->USER = OB_IWDG | (uint16_t)(OB_STOP | (uint16_t)(OB_STDBY | ((uint16_t)0xF8))); + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Configures to boot from Bank1 or Bank2. + * @note This function can be used only for STM32F10x_XL density devices. + * @param FLASH_BOOT: select the FLASH Bank to boot from. + * This parameter can be one of the following values: + * @arg FLASH_BOOT_Bank1: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank1(Default). + * @arg FLASH_BOOT_Bank2: At startup, if boot pins are set in boot from user Flash + * position and this parameter is selected the device will boot from Bank2 or Bank1, + * depending on the activation of the bank. The active banks are checked in + * the following order: Bank2, followed by Bank1. + * The active bank is recognized by the value programmed at the base address + * of the respective bank (corresponding to the initial stack pointer value + * in the interrupt vector table). + * For more information, please refer to AN2606 from www.st.com. + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_BootConfig(uint16_t FLASH_BOOT) +{ + FLASH_Status status = FLASH_COMPLETE; + assert_param(IS_FLASH_BOOT(FLASH_BOOT)); + /* Authorize the small information block programming */ + FLASH->OPTKEYR = FLASH_KEY1; + FLASH->OPTKEYR = FLASH_KEY2; + + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + + if(status == FLASH_COMPLETE) + { + /* Enable the Option Bytes Programming operation */ + FLASH->CR |= CR_OPTPG_Set; + + if(FLASH_BOOT == FLASH_BOOT_Bank1) + { + OB->USER |= OB_USER_BFB2; + } + else + { + OB->USER &= (uint16_t)(~(uint16_t)(OB_USER_BFB2)); + } + /* Wait for last operation to be completed */ + status = FLASH_WaitForLastOperation(ProgramTimeout); + if(status != FLASH_TIMEOUT) + { + /* if the program operation is completed, disable the OPTPG Bit */ + FLASH->CR &= CR_OPTPG_Reset; + } + } + /* Return the Option Byte program Status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @brief Returns the FLASH User Option Bytes values. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH User Option Bytes values:IWDG_SW(Bit0), RST_STOP(Bit1) + * and RST_STDBY(Bit2). + */ +uint32_t FLASH_GetUserOptionByte(void) +{ + /* Return the User Option Byte */ + return (uint32_t)(FLASH->OBR >> 2); +} + +/** + * @brief Returns the FLASH Write Protection Option Bytes Register value. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval The FLASH Write Protection Option Bytes Register value + */ +uint32_t FLASH_GetWriteProtectionOptionByte(void) +{ + /* Return the Flash write protection Register value */ + return (uint32_t)(FLASH->WRPR); +} + +/** + * @brief Checks whether the FLASH Read Out Protection Status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH ReadOut Protection Status(SET or RESET) + */ +FlagStatus FLASH_GetReadOutProtectionStatus(void) +{ + FlagStatus readoutstatus = RESET; + if ((FLASH->OBR & RDPRT_Mask) != (uint32_t)RESET) + { + readoutstatus = SET; + } + else + { + readoutstatus = RESET; + } + return readoutstatus; +} + +/** + * @brief Checks whether the FLASH Prefetch Buffer status is set or not. + * @note This function can be used for all STM32F10x devices. + * @param None + * @retval FLASH Prefetch Buffer Status (SET or RESET). + */ +FlagStatus FLASH_GetPrefetchBufferStatus(void) +{ + FlagStatus bitstatus = RESET; + + if ((FLASH->ACR & ACR_PRFTBS_Mask) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the new state of FLASH Prefetch Buffer Status (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Enables or disables the specified FLASH interrupts. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, enables or disables the specified FLASH interrupts + for Bank1 and Bank2. + * - For other devices it enables or disables the specified FLASH interrupts for Bank1. + * @param FLASH_IT: specifies the FLASH interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FLASH_IT_ERROR: FLASH Error Interrupt + * @arg FLASH_IT_EOP: FLASH end of operation Interrupt + * @param NewState: new state of the specified Flash interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FLASH_ITConfig(uint32_t FLASH_IT, FunctionalState NewState) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((FLASH_IT & 0x80000000) != 0x0) + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR2 |= (FLASH_IT & 0x7FFFFFFF); + } + else + { + /* Disable the interrupt sources */ + FLASH->CR2 &= ~(uint32_t)(FLASH_IT & 0x7FFFFFFF); + } + } + else + { + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_IT(FLASH_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if(NewState != DISABLE) + { + /* Enable the interrupt sources */ + FLASH->CR |= FLASH_IT; + } + else + { + /* Disable the interrupt sources */ + FLASH->CR &= ~(uint32_t)FLASH_IT; + } +#endif /* STM32F10X_XL */ +} + +/** + * @brief Checks whether the specified FLASH flag is set or not. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function checks whether the specified + * Bank1 or Bank2 flag is set or not. + * - For other devices, it checks whether the specified Bank1 flag is + * set or not. + * @param FLASH_FLAG: specifies the FLASH flag to check. + * This parameter can be one of the following values: + * @arg FLASH_FLAG_BSY: FLASH Busy flag + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @arg FLASH_FLAG_OPTERR: FLASH Option Byte error flag + * @retval The new state of FLASH_FLAG (SET or RESET). + */ +FlagStatus FLASH_GetFlagStatus(uint32_t FLASH_FLAG) +{ + FlagStatus bitstatus = RESET; + +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH_FLAG & 0x80000000) != 0x0) + { + if((FLASH->SR2 & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + } +#else + /* Check the parameters */ + assert_param(IS_FLASH_GET_FLAG(FLASH_FLAG)) ; + if(FLASH_FLAG == FLASH_FLAG_OPTERR) + { + if((FLASH->OBR & FLASH_FLAG_OPTERR) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } + else + { + if((FLASH->SR & FLASH_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + } +#endif /* STM32F10X_XL */ + + /* Return the new state of FLASH_FLAG (SET or RESET) */ + return bitstatus; +} + +/** + * @brief Clears the FLASH's pending flags. + * @note This function can be used for all STM32F10x devices. + * - For STM32F10X_XL devices, this function clears Bank1 or Bank2’s pending flags + * - For other devices, it clears Bank1’s pending flags. + * @param FLASH_FLAG: specifies the FLASH flags to clear. + * This parameter can be any combination of the following values: + * @arg FLASH_FLAG_PGERR: FLASH Program error flag + * @arg FLASH_FLAG_WRPRTERR: FLASH Write protected error flag + * @arg FLASH_FLAG_EOP: FLASH End of Operation flag + * @retval None + */ +void FLASH_ClearFlag(uint32_t FLASH_FLAG) +{ +#ifdef STM32F10X_XL + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + if((FLASH_FLAG & 0x80000000) != 0x0) + { + /* Clear the flags */ + FLASH->SR2 = FLASH_FLAG; + } + else + { + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; + } + +#else + /* Check the parameters */ + assert_param(IS_FLASH_CLEAR_FLAG(FLASH_FLAG)) ; + + /* Clear the flags */ + FLASH->SR = FLASH_FLAG; +#endif /* STM32F10X_XL */ +} + +/** + * @brief Returns the FLASH Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetBank1Status function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetStatus(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +/** + * @brief Returns the FLASH Bank1 Status. + * @note This function can be used for all STM32F10x devices, it is equivalent + * to FLASH_GetStatus function. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank1Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR & FLASH_FLAG_BANK1_BSY) == FLASH_FLAG_BSY) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_PGERR) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR & FLASH_FLAG_BANK1_WRPRTERR) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} + +#ifdef STM32F10X_XL +/** + * @brief Returns the FLASH Bank2 Status. + * @note This function can be used for STM32F10x_XL density devices. + * @param None + * @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG, + * FLASH_ERROR_WRP or FLASH_COMPLETE + */ +FLASH_Status FLASH_GetBank2Status(void) +{ + FLASH_Status flashstatus = FLASH_COMPLETE; + + if((FLASH->SR2 & (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) + { + flashstatus = FLASH_BUSY; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_PGERR & 0x7FFFFFFF)) != 0) + { + flashstatus = FLASH_ERROR_PG; + } + else + { + if((FLASH->SR2 & (FLASH_FLAG_BANK2_WRPRTERR & 0x7FFFFFFF)) != 0 ) + { + flashstatus = FLASH_ERROR_WRP; + } + else + { + flashstatus = FLASH_COMPLETE; + } + } + } + /* Return the Flash Status */ + return flashstatus; +} +#endif /* STM32F10X_XL */ +/** + * @brief Waits for a Flash operation to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastBank1Operation. + * - For STM32F10X_XL devices this function waits for a Bank1 Flash operation + * to complete or a TIMEOUT to occur. + * - For all other devices it waits for a Flash operation to complete + * or a TIMEOUT to occur. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastOperation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_BUSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +/** + * @brief Waits for a Flash operation on Bank1 to complete or a TIMEOUT to occur. + * @note This function can be used for all STM32F10x devices, + * it is equivalent to FLASH_WaitForLastOperation. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank1Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank1Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == FLASH_FLAG_BANK1_BSY) && (Timeout != 0x00)) + { + status = FLASH_GetBank1Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} + +#ifdef STM32F10X_XL +/** + * @brief Waits for a Flash operation on Bank2 to complete or a TIMEOUT to occur. + * @note This function can be used only for STM32F10x_XL density devices. + * @param Timeout: FLASH programming Timeout + * @retval FLASH Status: The returned value can be: FLASH_ERROR_PG, + * FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT. + */ +FLASH_Status FLASH_WaitForLastBank2Operation(uint32_t Timeout) +{ + FLASH_Status status = FLASH_COMPLETE; + + /* Check for the Flash Status */ + status = FLASH_GetBank2Status(); + /* Wait for a Flash operation to complete or a TIMEOUT to occur */ + while((status == (FLASH_FLAG_BANK2_BSY & 0x7FFFFFFF)) && (Timeout != 0x00)) + { + status = FLASH_GetBank2Status(); + Timeout--; + } + if(Timeout == 0x00 ) + { + status = FLASH_TIMEOUT; + } + /* Return the operation status */ + return status; +} +#endif /* STM32F10X_XL */ + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c new file mode 100755 index 0000000000..c75137cacb --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_fsmc.c @@ -0,0 +1,866 @@ +/** + ****************************************************************************** + * @file stm32f10x_fsmc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the FSMC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_fsmc.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup FSMC + * @brief FSMC driver modules + * @{ + */ + +/** @defgroup FSMC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup FSMC_Private_Defines + * @{ + */ + +/* --------------------- FSMC registers bit mask ---------------------------- */ + +/* FSMC BCRx Mask */ +#define BCR_MBKEN_Set ((uint32_t)0x00000001) +#define BCR_MBKEN_Reset ((uint32_t)0x000FFFFE) +#define BCR_FACCEN_Set ((uint32_t)0x00000040) + +/* FSMC PCRx Mask */ +#define PCR_PBKEN_Set ((uint32_t)0x00000004) +#define PCR_PBKEN_Reset ((uint32_t)0x000FFFFB) +#define PCR_ECCEN_Set ((uint32_t)0x00000040) +#define PCR_ECCEN_Reset ((uint32_t)0x000FFFBF) +#define PCR_MemoryType_NAND ((uint32_t)0x00000008) +/** + * @} + */ + +/** @defgroup FSMC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup FSMC_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the FSMC NOR/SRAM Banks registers to their default + * reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @retval None + */ +void FSMC_NORSRAMDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + + /* FSMC_Bank1_NORSRAM1 */ + if(FSMC_Bank == FSMC_Bank1_NORSRAM1) + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030DB; + } + /* FSMC_Bank1_NORSRAM2, FSMC_Bank1_NORSRAM3 or FSMC_Bank1_NORSRAM4 */ + else + { + FSMC_Bank1->BTCR[FSMC_Bank] = 0x000030D2; + } + FSMC_Bank1->BTCR[FSMC_Bank + 1] = 0x0FFFFFFF; + FSMC_Bank1E->BWTR[FSMC_Bank] = 0x0FFFFFFF; +} + +/** + * @brief Deinitializes the FSMC NAND Banks registers to their default reset values. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval None + */ +void FSMC_NANDDeInit(uint32_t FSMC_Bank) +{ + /* Check the parameter */ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Set the FSMC_Bank2 registers to their reset values */ + FSMC_Bank2->PCR2 = 0x00000018; + FSMC_Bank2->SR2 = 0x00000040; + FSMC_Bank2->PMEM2 = 0xFCFCFCFC; + FSMC_Bank2->PATT2 = 0xFCFCFCFC; + } + /* FSMC_Bank3_NAND */ + else + { + /* Set the FSMC_Bank3 registers to their reset values */ + FSMC_Bank3->PCR3 = 0x00000018; + FSMC_Bank3->SR3 = 0x00000040; + FSMC_Bank3->PMEM3 = 0xFCFCFCFC; + FSMC_Bank3->PATT3 = 0xFCFCFCFC; + } +} + +/** + * @brief Deinitializes the FSMC PCCARD Bank registers to their default reset values. + * @param None + * @retval None + */ +void FSMC_PCCARDDeInit(void) +{ + /* Set the FSMC_Bank4 registers to their reset values */ + FSMC_Bank4->PCR4 = 0x00000018; + FSMC_Bank4->SR4 = 0x00000000; + FSMC_Bank4->PMEM4 = 0xFCFCFCFC; + FSMC_Bank4->PATT4 = 0xFCFCFCFC; + FSMC_Bank4->PIO4 = 0xFCFCFCFC; +} + +/** + * @brief Initializes the FSMC NOR/SRAM Banks according to the specified + * parameters in the FSMC_NORSRAMInitStruct. + * @param FSMC_NORSRAMInitStruct : pointer to a FSMC_NORSRAMInitTypeDef + * structure that contains the configuration information for + * the FSMC NOR/SRAM specified Banks. + * @retval None + */ +void FSMC_NORSRAMInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_NORSRAMInitStruct->FSMC_Bank)); + assert_param(IS_FSMC_MUX(FSMC_NORSRAMInitStruct->FSMC_DataAddressMux)); + assert_param(IS_FSMC_MEMORY(FSMC_NORSRAMInitStruct->FSMC_MemoryType)); + assert_param(IS_FSMC_MEMORY_WIDTH(FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth)); + assert_param(IS_FSMC_BURSTMODE(FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode)); + assert_param(IS_FSMC_ASYNWAIT(FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait)); + assert_param(IS_FSMC_WAIT_POLARITY(FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity)); + assert_param(IS_FSMC_WRAP_MODE(FSMC_NORSRAMInitStruct->FSMC_WrapMode)); + assert_param(IS_FSMC_WAIT_SIGNAL_ACTIVE(FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive)); + assert_param(IS_FSMC_WRITE_OPERATION(FSMC_NORSRAMInitStruct->FSMC_WriteOperation)); + assert_param(IS_FSMC_WAITE_SIGNAL(FSMC_NORSRAMInitStruct->FSMC_WaitSignal)); + assert_param(IS_FSMC_EXTENDED_MODE(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode)); + assert_param(IS_FSMC_WRITE_BURST(FSMC_NORSRAMInitStruct->FSMC_WriteBurst)); + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_TURNAROUND_TIME(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode)); + + /* Bank1 NOR/SRAM control register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_DataAddressMux | + FSMC_NORSRAMInitStruct->FSMC_MemoryType | + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth | + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode | + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity | + FSMC_NORSRAMInitStruct->FSMC_WrapMode | + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive | + FSMC_NORSRAMInitStruct->FSMC_WriteOperation | + FSMC_NORSRAMInitStruct->FSMC_WaitSignal | + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode | + FSMC_NORSRAMInitStruct->FSMC_WriteBurst; + + if(FSMC_NORSRAMInitStruct->FSMC_MemoryType == FSMC_MemoryType_NOR) + { + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank] |= (uint32_t)BCR_FACCEN_Set; + } + + /* Bank1 NOR/SRAM timing register configuration */ + FSMC_Bank1->BTCR[FSMC_NORSRAMInitStruct->FSMC_Bank+1] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime << 4) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration << 16) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode; + + + /* Bank1 NOR/SRAM timing register for write configuration, if extended mode is used */ + if(FSMC_NORSRAMInitStruct->FSMC_ExtendedMode == FSMC_ExtendedMode_Enable) + { + assert_param(IS_FSMC_ADDRESS_SETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime)); + assert_param(IS_FSMC_ADDRESS_HOLD_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime)); + assert_param(IS_FSMC_DATASETUP_TIME(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime)); + assert_param(IS_FSMC_CLK_DIV(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision)); + assert_param(IS_FSMC_DATA_LATENCY(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency)); + assert_param(IS_FSMC_ACCESS_MODE(FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode)); + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = + (uint32_t)FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime << 4 )| + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime << 8) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision << 20) | + (FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency << 24) | + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode; + } + else + { + FSMC_Bank1E->BWTR[FSMC_NORSRAMInitStruct->FSMC_Bank] = 0x0FFFFFFF; + } +} + +/** + * @brief Initializes the FSMC NAND Banks according to the specified + * parameters in the FSMC_NANDInitStruct. + * @param FSMC_NANDInitStruct : pointer to a FSMC_NANDInitTypeDef + * structure that contains the configuration information for the FSMC + * NAND specified Banks. + * @retval None + */ +void FSMC_NANDInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + uint32_t tmppcr = 0x00000000, tmppmem = 0x00000000, tmppatt = 0x00000000; + + /* Check the parameters */ + assert_param( IS_FSMC_NAND_BANK(FSMC_NANDInitStruct->FSMC_Bank)); + assert_param( IS_FSMC_WAIT_FEATURE(FSMC_NANDInitStruct->FSMC_Waitfeature)); + assert_param( IS_FSMC_MEMORY_WIDTH(FSMC_NANDInitStruct->FSMC_MemoryDataWidth)); + assert_param( IS_FSMC_ECC_STATE(FSMC_NANDInitStruct->FSMC_ECC)); + assert_param( IS_FSMC_ECCPAGE_SIZE(FSMC_NANDInitStruct->FSMC_ECCPageSize)); + assert_param( IS_FSMC_TCLR_TIME(FSMC_NANDInitStruct->FSMC_TCLRSetupTime)); + assert_param( IS_FSMC_TAR_TIME(FSMC_NANDInitStruct->FSMC_TARSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the tmppcr value according to FSMC_NANDInitStruct parameters */ + tmppcr = (uint32_t)FSMC_NANDInitStruct->FSMC_Waitfeature | + PCR_MemoryType_NAND | + FSMC_NANDInitStruct->FSMC_MemoryDataWidth | + FSMC_NANDInitStruct->FSMC_ECC | + FSMC_NANDInitStruct->FSMC_ECCPageSize | + (FSMC_NANDInitStruct->FSMC_TCLRSetupTime << 9 )| + (FSMC_NANDInitStruct->FSMC_TARSetupTime << 13); + + /* Set tmppmem value according to FSMC_CommonSpaceTimingStructure parameters */ + tmppmem = (uint32_t)FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set tmppatt value according to FSMC_AttributeSpaceTimingStructure parameters */ + tmppatt = (uint32_t)FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + if(FSMC_NANDInitStruct->FSMC_Bank == FSMC_Bank2_NAND) + { + /* FSMC_Bank2_NAND registers configuration */ + FSMC_Bank2->PCR2 = tmppcr; + FSMC_Bank2->PMEM2 = tmppmem; + FSMC_Bank2->PATT2 = tmppatt; + } + else + { + /* FSMC_Bank3_NAND registers configuration */ + FSMC_Bank3->PCR3 = tmppcr; + FSMC_Bank3->PMEM3 = tmppmem; + FSMC_Bank3->PATT3 = tmppatt; + } +} + +/** + * @brief Initializes the FSMC PCCARD Bank according to the specified + * parameters in the FSMC_PCCARDInitStruct. + * @param FSMC_PCCARDInitStruct : pointer to a FSMC_PCCARDInitTypeDef + * structure that contains the configuration information for the FSMC + * PCCARD Bank. + * @retval None + */ +void FSMC_PCCARDInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Check the parameters */ + assert_param(IS_FSMC_WAIT_FEATURE(FSMC_PCCARDInitStruct->FSMC_Waitfeature)); + assert_param(IS_FSMC_TCLR_TIME(FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime)); + assert_param(IS_FSMC_TAR_TIME(FSMC_PCCARDInitStruct->FSMC_TARSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime)); + + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime)); + assert_param(IS_FSMC_SETUP_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime)); + assert_param(IS_FSMC_WAIT_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime)); + assert_param(IS_FSMC_HOLD_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime)); + assert_param(IS_FSMC_HIZ_TIME(FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime)); + + /* Set the PCR4 register value according to FSMC_PCCARDInitStruct parameters */ + FSMC_Bank4->PCR4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_Waitfeature | + FSMC_MemoryDataWidth_16b | + (FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime << 9) | + (FSMC_PCCARDInitStruct->FSMC_TARSetupTime << 13); + + /* Set PMEM4 register value according to FSMC_CommonSpaceTimingStructure parameters */ + FSMC_Bank4->PMEM4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PATT4 register value according to FSMC_AttributeSpaceTimingStructure parameters */ + FSMC_Bank4->PATT4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime << 24); + + /* Set PIO4 register value according to FSMC_IOSpaceTimingStructure parameters */ + FSMC_Bank4->PIO4 = (uint32_t)FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime << 8) | + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime << 16)| + (FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime << 24); +} + +/** + * @brief Fills each FSMC_NORSRAMInitStruct member with its default value. + * @param FSMC_NORSRAMInitStruct: pointer to a FSMC_NORSRAMInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NORSRAMStructInit(FSMC_NORSRAMInitTypeDef* FSMC_NORSRAMInitStruct) +{ + /* Reset NOR/SRAM Init structure parameters values */ + FSMC_NORSRAMInitStruct->FSMC_Bank = FSMC_Bank1_NORSRAM1; + FSMC_NORSRAMInitStruct->FSMC_DataAddressMux = FSMC_DataAddressMux_Enable; + FSMC_NORSRAMInitStruct->FSMC_MemoryType = FSMC_MemoryType_SRAM; + FSMC_NORSRAMInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NORSRAMInitStruct->FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; + FSMC_NORSRAMInitStruct->FSMC_WrapMode = FSMC_WrapMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; + FSMC_NORSRAMInitStruct->FSMC_WriteOperation = FSMC_WriteOperation_Enable; + FSMC_NORSRAMInitStruct->FSMC_WaitSignal = FSMC_WaitSignal_Enable; + FSMC_NORSRAMInitStruct->FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; + FSMC_NORSRAMInitStruct->FSMC_WriteBurst = FSMC_WriteBurst_Disable; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_ReadWriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressSetupTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AddressHoldTime = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataSetupTime = 0xFF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_BusTurnAroundDuration = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_CLKDivision = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_DataLatency = 0xF; + FSMC_NORSRAMInitStruct->FSMC_WriteTimingStruct->FSMC_AccessMode = FSMC_AccessMode_A; +} + +/** + * @brief Fills each FSMC_NANDInitStruct member with its default value. + * @param FSMC_NANDInitStruct: pointer to a FSMC_NANDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_NANDStructInit(FSMC_NANDInitTypeDef* FSMC_NANDInitStruct) +{ + /* Reset NAND Init structure parameters values */ + FSMC_NANDInitStruct->FSMC_Bank = FSMC_Bank2_NAND; + FSMC_NANDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_NANDInitStruct->FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_8b; + FSMC_NANDInitStruct->FSMC_ECC = FSMC_ECC_Disable; + FSMC_NANDInitStruct->FSMC_ECCPageSize = FSMC_ECCPageSize_256Bytes; + FSMC_NANDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_NANDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Fills each FSMC_PCCARDInitStruct member with its default value. + * @param FSMC_PCCARDInitStruct: pointer to a FSMC_PCCARDInitTypeDef + * structure which will be initialized. + * @retval None + */ +void FSMC_PCCARDStructInit(FSMC_PCCARDInitTypeDef* FSMC_PCCARDInitStruct) +{ + /* Reset PCCARD Init structure parameters values */ + FSMC_PCCARDInitStruct->FSMC_Waitfeature = FSMC_Waitfeature_Disable; + FSMC_PCCARDInitStruct->FSMC_TCLRSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_TARSetupTime = 0x0; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_CommonSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_AttributeSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_SetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_WaitSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HoldSetupTime = 0xFC; + FSMC_PCCARDInitStruct->FSMC_IOSpaceTimingStruct->FSMC_HiZSetupTime = 0xFC; +} + +/** + * @brief Enables or disables the specified NOR/SRAM Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank1_NORSRAM1: FSMC Bank1 NOR/SRAM1 + * @arg FSMC_Bank1_NORSRAM2: FSMC Bank1 NOR/SRAM2 + * @arg FSMC_Bank1_NORSRAM3: FSMC Bank1 NOR/SRAM3 + * @arg FSMC_Bank1_NORSRAM4: FSMC Bank1 NOR/SRAM4 + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NORSRAMCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NORSRAM_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NOR/SRAM Bank by setting the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] |= BCR_MBKEN_Set; + } + else + { + /* Disable the selected NOR/SRAM Bank by clearing the PBKEN bit in the BCRx register */ + FSMC_Bank1->BTCR[FSMC_Bank] &= BCR_MBKEN_Reset; + } +} + +/** + * @brief Enables or disables the specified NAND Memory Bank. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC_Bank. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank by setting the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_PBKEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_PBKEN_Set; + } + } + else + { + /* Disable the selected NAND Bank by clearing the PBKEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_PBKEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_PBKEN_Reset; + } + } +} + +/** + * @brief Enables or disables the PCCARD Memory Bank. + * @param NewState: new state of the PCCARD Memory Bank. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_PCCARDCmd(FunctionalState NewState) +{ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the PCCARD Bank by setting the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 |= PCR_PBKEN_Set; + } + else + { + /* Disable the PCCARD Bank by clearing the PBKEN bit in the PCR4 register */ + FSMC_Bank4->PCR4 &= PCR_PBKEN_Reset; + } +} + +/** + * @brief Enables or disables the FSMC NAND ECC feature. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @param NewState: new state of the FSMC NAND ECC feature. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_NANDECCCmd(uint32_t FSMC_Bank, FunctionalState NewState) +{ + assert_param(IS_FSMC_NAND_BANK(FSMC_Bank)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected NAND Bank ECC function by setting the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 |= PCR_ECCEN_Set; + } + else + { + FSMC_Bank3->PCR3 |= PCR_ECCEN_Set; + } + } + else + { + /* Disable the selected NAND Bank ECC function by clearing the ECCEN bit in the PCRx register */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->PCR2 &= PCR_ECCEN_Reset; + } + else + { + FSMC_Bank3->PCR3 &= PCR_ECCEN_Reset; + } + } +} + +/** + * @brief Returns the error correction code register value. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @retval The Error Correction Code (ECC) value. + */ +uint32_t FSMC_GetECC(uint32_t FSMC_Bank) +{ + uint32_t eccval = 0x00000000; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + /* Get the ECCR2 register value */ + eccval = FSMC_Bank2->ECCR2; + } + else + { + /* Get the ECCR3 register value */ + eccval = FSMC_Bank3->ECCR3; + } + /* Return the error correction code value */ + return(eccval); +} + +/** + * @brief Enables or disables the specified FSMC interrupts. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @param NewState: new state of the specified FSMC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void FSMC_ITConfig(uint32_t FSMC_Bank, uint32_t FSMC_IT, FunctionalState NewState) +{ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 |= FSMC_IT; + } + /* Enable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 |= FSMC_IT; + } + } + else + { + /* Disable the selected FSMC_Bank2 interrupts */ + if(FSMC_Bank == FSMC_Bank2_NAND) + { + + FSMC_Bank2->SR2 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank3 interrupts */ + else if (FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= (uint32_t)~FSMC_IT; + } + /* Disable the selected FSMC_Bank4 interrupts */ + else + { + FSMC_Bank4->SR4 &= (uint32_t)~FSMC_IT; + } + } +} + +/** + * @brief Checks whether the specified FSMC flag is set or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @arg FSMC_FLAG_FEMPT: Fifo empty Flag. + * @retval The new state of FSMC_FLAG (SET or RESET). + */ +FlagStatus FSMC_GetFlagStatus(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + FlagStatus bitstatus = RESET; + uint32_t tmpsr = 0x00000000; + + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_FLAG(FSMC_FLAG)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + /* Get the flag status */ + if ((tmpsr & FSMC_FLAG) != (uint16_t)RESET ) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the FSMC's pending flags. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_FLAG_RisingEdge: Rising egde detection Flag. + * @arg FSMC_FLAG_Level: Level detection Flag. + * @arg FSMC_FLAG_FallingEdge: Falling egde detection Flag. + * @retval None + */ +void FSMC_ClearFlag(uint32_t FSMC_Bank, uint32_t FSMC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_FSMC_GETFLAG_BANK(FSMC_Bank)); + assert_param(IS_FSMC_CLEAR_FLAG(FSMC_FLAG)) ; + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~FSMC_FLAG; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~FSMC_FLAG; + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~FSMC_FLAG; + } +} + +/** + * @brief Checks whether the specified FSMC interrupt has occurred or not. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the FSMC interrupt source to check. + * This parameter can be one of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval The new state of FSMC_IT (SET or RESET). + */ +ITStatus FSMC_GetITStatus(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + ITStatus bitstatus = RESET; + uint32_t tmpsr = 0x0, itstatus = 0x0, itenable = 0x0; + + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_GET_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + tmpsr = FSMC_Bank2->SR2; + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + tmpsr = FSMC_Bank3->SR3; + } + /* FSMC_Bank4_PCCARD*/ + else + { + tmpsr = FSMC_Bank4->SR4; + } + + itstatus = tmpsr & FSMC_IT; + + itenable = tmpsr & (FSMC_IT >> 3); + if ((itstatus != (uint32_t)RESET) && (itenable != (uint32_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the FSMC's interrupt pending bits. + * @param FSMC_Bank: specifies the FSMC Bank to be used + * This parameter can be one of the following values: + * @arg FSMC_Bank2_NAND: FSMC Bank2 NAND + * @arg FSMC_Bank3_NAND: FSMC Bank3 NAND + * @arg FSMC_Bank4_PCCARD: FSMC Bank4 PCCARD + * @param FSMC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg FSMC_IT_RisingEdge: Rising edge detection interrupt. + * @arg FSMC_IT_Level: Level edge detection interrupt. + * @arg FSMC_IT_FallingEdge: Falling edge detection interrupt. + * @retval None + */ +void FSMC_ClearITPendingBit(uint32_t FSMC_Bank, uint32_t FSMC_IT) +{ + /* Check the parameters */ + assert_param(IS_FSMC_IT_BANK(FSMC_Bank)); + assert_param(IS_FSMC_IT(FSMC_IT)); + + if(FSMC_Bank == FSMC_Bank2_NAND) + { + FSMC_Bank2->SR2 &= ~(FSMC_IT >> 3); + } + else if(FSMC_Bank == FSMC_Bank3_NAND) + { + FSMC_Bank3->SR3 &= ~(FSMC_IT >> 3); + } + /* FSMC_Bank4_PCCARD*/ + else + { + FSMC_Bank4->SR4 &= ~(FSMC_IT >> 3); + } +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c new file mode 100755 index 0000000000..93dbcd7caf --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_gpio.c @@ -0,0 +1,650 @@ +/** + ****************************************************************************** + * @file stm32f10x_gpio.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the GPIO firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_gpio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup GPIO + * @brief GPIO driver modules + * @{ + */ + +/** @defgroup GPIO_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------------*/ +#define AFIO_OFFSET (AFIO_BASE - PERIPH_BASE) + +/* --- EVENTCR Register -----*/ + +/* Alias word address of EVOE bit */ +#define EVCR_OFFSET (AFIO_OFFSET + 0x00) +#define EVOE_BitNumber ((uint8_t)0x07) +#define EVCR_EVOE_BB (PERIPH_BB_BASE + (EVCR_OFFSET * 32) + (EVOE_BitNumber * 4)) + + +/* --- MAPR Register ---*/ +/* Alias word address of MII_RMII_SEL bit */ +#define MAPR_OFFSET (AFIO_OFFSET + 0x04) +#define MII_RMII_SEL_BitNumber ((u8)0x17) +#define MAPR_MII_RMII_SEL_BB (PERIPH_BB_BASE + (MAPR_OFFSET * 32) + (MII_RMII_SEL_BitNumber * 4)) + + +#define EVCR_PORTPINCONFIG_MASK ((uint16_t)0xFF80) +#define LSB_MASK ((uint16_t)0xFFFF) +#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000) +#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF) +#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000) +#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000) +/** + * @} + */ + +/** @defgroup GPIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup GPIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the GPIOx peripheral registers to their default reset values. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval None + */ +void GPIO_DeInit(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + if (GPIOx == GPIOA) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOA, DISABLE); + } + else if (GPIOx == GPIOB) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOB, DISABLE); + } + else if (GPIOx == GPIOC) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOC, DISABLE); + } + else if (GPIOx == GPIOD) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOD, DISABLE); + } + else if (GPIOx == GPIOE) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOE, DISABLE); + } + else if (GPIOx == GPIOF) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOF, DISABLE); + } + else + { + if (GPIOx == GPIOG) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_GPIOG, DISABLE); + } + } +} + +/** + * @brief Deinitializes the Alternate Functions (remap, event control + * and EXTI configuration) registers to their default reset values. + * @param None + * @retval None + */ +void GPIO_AFIODeInit(void) +{ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_AFIO, DISABLE); +} + +/** + * @brief Initializes the GPIOx peripheral according to the specified + * parameters in the GPIO_InitStruct. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_InitStruct: pointer to a GPIO_InitTypeDef structure that + * contains the configuration information for the specified GPIO peripheral. + * @retval None + */ +void GPIO_Init(GPIO_TypeDef* GPIOx, GPIO_InitTypeDef* GPIO_InitStruct) +{ + uint32_t currentmode = 0x00, currentpin = 0x00, pinpos = 0x00, pos = 0x00; + uint32_t tmpreg = 0x00, pinmask = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_MODE(GPIO_InitStruct->GPIO_Mode)); + assert_param(IS_GPIO_PIN(GPIO_InitStruct->GPIO_Pin)); + +/*---------------------------- GPIO Mode Configuration -----------------------*/ + currentmode = ((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x0F); + if ((((uint32_t)GPIO_InitStruct->GPIO_Mode) & ((uint32_t)0x10)) != 0x00) + { + /* Check the parameters */ + assert_param(IS_GPIO_SPEED(GPIO_InitStruct->GPIO_Speed)); + /* Output mode */ + currentmode |= (uint32_t)GPIO_InitStruct->GPIO_Speed; + } +/*---------------------------- GPIO CRL Configuration ------------------------*/ + /* Configure the eight low port pins */ + if (((uint32_t)GPIO_InitStruct->GPIO_Pin & ((uint32_t)0x00FF)) != 0x00) + { + tmpreg = GPIOx->CRL; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = ((uint32_t)0x01) << pinpos; + /* Get the port pins position */ + currentpin = (GPIO_InitStruct->GPIO_Pin) & pos; + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding low control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << pinpos); + } + else + { + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << pinpos); + } + } + } + } + GPIOx->CRL = tmpreg; + } +/*---------------------------- GPIO CRH Configuration ------------------------*/ + /* Configure the eight high port pins */ + if (GPIO_InitStruct->GPIO_Pin > 0x00FF) + { + tmpreg = GPIOx->CRH; + for (pinpos = 0x00; pinpos < 0x08; pinpos++) + { + pos = (((uint32_t)0x01) << (pinpos + 0x08)); + /* Get the port pins position */ + currentpin = ((GPIO_InitStruct->GPIO_Pin) & pos); + if (currentpin == pos) + { + pos = pinpos << 2; + /* Clear the corresponding high control register bits */ + pinmask = ((uint32_t)0x0F) << pos; + tmpreg &= ~pinmask; + /* Write the mode configuration in the corresponding bits */ + tmpreg |= (currentmode << pos); + /* Reset the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPD) + { + GPIOx->BRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + /* Set the corresponding ODR bit */ + if (GPIO_InitStruct->GPIO_Mode == GPIO_Mode_IPU) + { + GPIOx->BSRR = (((uint32_t)0x01) << (pinpos + 0x08)); + } + } + } + GPIOx->CRH = tmpreg; + } +} + +/** + * @brief Fills each GPIO_InitStruct member with its default value. + * @param GPIO_InitStruct : pointer to a GPIO_InitTypeDef structure which will + * be initialized. + * @retval None + */ +void GPIO_StructInit(GPIO_InitTypeDef* GPIO_InitStruct) +{ + /* Reset GPIO init structure parameters values */ + GPIO_InitStruct->GPIO_Pin = GPIO_Pin_All; + GPIO_InitStruct->GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStruct->GPIO_Mode = GPIO_Mode_IN_FLOATING; +} + +/** + * @brief Reads the specified input port pin. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The input port pin value. + */ +uint8_t GPIO_ReadInputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->IDR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO input data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO input data port value. + */ +uint16_t GPIO_ReadInputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->IDR); +} + +/** + * @brief Reads the specified output data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to read. + * This parameter can be GPIO_Pin_x where x can be (0..15). + * @retval The output port pin value. + */ +uint8_t GPIO_ReadOutputDataBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint8_t bitstatus = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + + if ((GPIOx->ODR & GPIO_Pin) != (uint32_t)Bit_RESET) + { + bitstatus = (uint8_t)Bit_SET; + } + else + { + bitstatus = (uint8_t)Bit_RESET; + } + return bitstatus; +} + +/** + * @brief Reads the specified GPIO output data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @retval GPIO output data port value. + */ +uint16_t GPIO_ReadOutputData(GPIO_TypeDef* GPIOx) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + return ((uint16_t)GPIOx->ODR); +} + +/** + * @brief Sets the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_SetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BSRR = GPIO_Pin; +} + +/** + * @brief Clears the selected data port bits. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bits to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_ResetBits(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + GPIOx->BRR = GPIO_Pin; +} + +/** + * @brief Sets or clears the selected data port bit. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be one of GPIO_Pin_x where x can be (0..15). + * @param BitVal: specifies the value to be written to the selected bit. + * This parameter can be one of the BitAction enum values: + * @arg Bit_RESET: to clear the port pin + * @arg Bit_SET: to set the port pin + * @retval None + */ +void GPIO_WriteBit(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, BitAction BitVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GET_GPIO_PIN(GPIO_Pin)); + assert_param(IS_GPIO_BIT_ACTION(BitVal)); + + if (BitVal != Bit_RESET) + { + GPIOx->BSRR = GPIO_Pin; + } + else + { + GPIOx->BRR = GPIO_Pin; + } +} + +/** + * @brief Writes data to the specified GPIO data port. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param PortVal: specifies the value to be written to the port output data register. + * @retval None + */ +void GPIO_Write(GPIO_TypeDef* GPIOx, uint16_t PortVal) +{ + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + + GPIOx->ODR = PortVal; +} + +/** + * @brief Locks GPIO Pins configuration registers. + * @param GPIOx: where x can be (A..G) to select the GPIO peripheral. + * @param GPIO_Pin: specifies the port bit to be written. + * This parameter can be any combination of GPIO_Pin_x where x can be (0..15). + * @retval None + */ +void GPIO_PinLockConfig(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin) +{ + uint32_t tmp = 0x00010000; + + /* Check the parameters */ + assert_param(IS_GPIO_ALL_PERIPH(GPIOx)); + assert_param(IS_GPIO_PIN(GPIO_Pin)); + + tmp |= GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Reset LCKK bit */ + GPIOx->LCKR = GPIO_Pin; + /* Set LCKK bit */ + GPIOx->LCKR = tmp; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; + /* Read LCKK bit*/ + tmp = GPIOx->LCKR; +} + +/** + * @brief Selects the GPIO pin used as Event output. + * @param GPIO_PortSource: selects the GPIO port to be used as source + * for Event output. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..E). + * @param GPIO_PinSource: specifies the pin for the Event output. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EventOutputConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EVENTOUT_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmpreg = AFIO->EVCR; + /* Clear the PORT[6:4] and PIN[3:0] bits */ + tmpreg &= EVCR_PORTPINCONFIG_MASK; + tmpreg |= (uint32_t)GPIO_PortSource << 0x04; + tmpreg |= GPIO_PinSource; + AFIO->EVCR = tmpreg; +} + +/** + * @brief Enables or disables the Event Output. + * @param NewState: new state of the Event output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_EventOutputCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) EVCR_EVOE_BB = (uint32_t)NewState; +} + +/** + * @brief Changes the mapping of the specified pin. + * @param GPIO_Remap: selects the pin to remap. + * This parameter can be one of the following values: + * @arg GPIO_Remap_SPI1 : SPI1 Alternate Function mapping + * @arg GPIO_Remap_I2C1 : I2C1 Alternate Function mapping + * @arg GPIO_Remap_USART1 : USART1 Alternate Function mapping + * @arg GPIO_Remap_USART2 : USART2 Alternate Function mapping + * @arg GPIO_PartialRemap_USART3 : USART3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_USART3 : USART3 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM1 : TIM1 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM1 : TIM1 Full Alternate Function mapping + * @arg GPIO_PartialRemap1_TIM2 : TIM2 Partial1 Alternate Function mapping + * @arg GPIO_PartialRemap2_TIM2 : TIM2 Partial2 Alternate Function mapping + * @arg GPIO_FullRemap_TIM2 : TIM2 Full Alternate Function mapping + * @arg GPIO_PartialRemap_TIM3 : TIM3 Partial Alternate Function mapping + * @arg GPIO_FullRemap_TIM3 : TIM3 Full Alternate Function mapping + * @arg GPIO_Remap_TIM4 : TIM4 Alternate Function mapping + * @arg GPIO_Remap1_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap2_CAN1 : CAN1 Alternate Function mapping + * @arg GPIO_Remap_PD01 : PD01 Alternate Function mapping + * @arg GPIO_Remap_TIM5CH4_LSI : LSI connected to TIM5 Channel4 input capture for calibration + * @arg GPIO_Remap_ADC1_ETRGINJ : ADC1 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC1_ETRGREG : ADC1 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGINJ : ADC2 External Trigger Injected Conversion remapping + * @arg GPIO_Remap_ADC2_ETRGREG : ADC2 External Trigger Regular Conversion remapping + * @arg GPIO_Remap_ETH : Ethernet remapping (only for Connectivity line devices) + * @arg GPIO_Remap_CAN2 : CAN2 remapping (only for Connectivity line devices) + * @arg GPIO_Remap_SWJ_NoJTRST : Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST + * @arg GPIO_Remap_SWJ_JTAGDisable : JTAG-DP Disabled and SW-DP Enabled + * @arg GPIO_Remap_SWJ_Disable : Full SWJ Disabled (JTAG-DP + SW-DP) + * @arg GPIO_Remap_SPI3 : SPI3/I2S3 Alternate Function mapping (only for Connectivity line devices) + * When the SPI3/I2S3 is remapped using this function, the SWJ is configured + * to Full SWJ Enabled (JTAG-DP + SW-DP) but without JTRST. + * @arg GPIO_Remap_TIM2ITR1_PTP_SOF : Ethernet PTP output or USB OTG SOF (Start of Frame) connected + * to TIM2 Internal Trigger 1 for calibration (only for Connectivity line devices) + * If the GPIO_Remap_TIM2ITR1_PTP_SOF is enabled the TIM2 ITR1 is connected to + * Ethernet PTP output. When Reset TIM2 ITR1 is connected to USB OTG SOF output. + * @arg GPIO_Remap_PTP_PPS : Ethernet MAC PPS_PTS output on PB05 (only for Connectivity line devices) + * @arg GPIO_Remap_TIM15 : TIM15 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM16 : TIM16 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM17 : TIM17 Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_CEC : CEC Alternate Function mapping (only for Value line devices) + * @arg GPIO_Remap_TIM1_DMA : TIM1 DMA requests mapping (only for Value line devices) + * @arg GPIO_Remap_TIM9 : TIM9 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM10 : TIM10 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM11 : TIM11 Alternate Function mapping (only for XL-density devices) + * @arg GPIO_Remap_TIM13 : TIM13 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM14 : TIM14 Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_FSMC_NADV : FSMC_NADV Alternate Function mapping (only for High density Value line and XL-density devices) + * @arg GPIO_Remap_TIM67_DAC_DMA : TIM6/TIM7 and DAC DMA requests remapping (only for High density Value line devices) + * @arg GPIO_Remap_TIM12 : TIM12 Alternate Function mapping (only for High density Value line devices) + * @arg GPIO_Remap_MISC : Miscellaneous Remap (DMA2 Channel5 Position and DAC Trigger remapping, + * only for High density Value line devices) + * @param NewState: new state of the port pin remapping. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void GPIO_PinRemapConfig(uint32_t GPIO_Remap, FunctionalState NewState) +{ + uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00; + + /* Check the parameters */ + assert_param(IS_GPIO_REMAP(GPIO_Remap)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + tmpreg = AFIO->MAPR2; + } + else + { + tmpreg = AFIO->MAPR; + } + + tmpmask = (GPIO_Remap & DBGAFR_POSITION_MASK) >> 0x10; + tmp = GPIO_Remap & LSB_MASK; + + if ((GPIO_Remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) + { + tmpreg &= DBGAFR_SWJCFG_MASK; + AFIO->MAPR &= DBGAFR_SWJCFG_MASK; + } + else if ((GPIO_Remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) + { + tmp1 = ((uint32_t)0x03) << tmpmask; + tmpreg &= ~tmp1; + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + else + { + tmpreg &= ~(tmp << ((GPIO_Remap >> 0x15)*0x10)); + tmpreg |= ~DBGAFR_SWJCFG_MASK; + } + + if (NewState != DISABLE) + { + tmpreg |= (tmp << ((GPIO_Remap >> 0x15)*0x10)); + } + + if((GPIO_Remap & 0x80000000) == 0x80000000) + { + AFIO->MAPR2 = tmpreg; + } + else + { + AFIO->MAPR = tmpreg; + } +} + +/** + * @brief Selects the GPIO pin used as EXTI Line. + * @param GPIO_PortSource: selects the GPIO port to be used as source for EXTI lines. + * This parameter can be GPIO_PortSourceGPIOx where x can be (A..G). + * @param GPIO_PinSource: specifies the EXTI line to be configured. + * This parameter can be GPIO_PinSourcex where x can be (0..15). + * @retval None + */ +void GPIO_EXTILineConfig(uint8_t GPIO_PortSource, uint8_t GPIO_PinSource) +{ + uint32_t tmp = 0x00; + /* Check the parameters */ + assert_param(IS_GPIO_EXTI_PORT_SOURCE(GPIO_PortSource)); + assert_param(IS_GPIO_PIN_SOURCE(GPIO_PinSource)); + + tmp = ((uint32_t)0x0F) << (0x04 * (GPIO_PinSource & (uint8_t)0x03)); + AFIO->EXTICR[GPIO_PinSource >> 0x02] &= ~tmp; + AFIO->EXTICR[GPIO_PinSource >> 0x02] |= (((uint32_t)GPIO_PortSource) << (0x04 * (GPIO_PinSource & (uint8_t)0x03))); +} + +/** + * @brief Selects the Ethernet media interface. + * @note This function applies only to STM32 Connectivity line devices. + * @param GPIO_ETH_MediaInterface: specifies the Media Interface mode. + * This parameter can be one of the following values: + * @arg GPIO_ETH_MediaInterface_MII: MII mode + * @arg GPIO_ETH_MediaInterface_RMII: RMII mode + * @retval None + */ +void GPIO_ETH_MediaInterfaceConfig(uint32_t GPIO_ETH_MediaInterface) +{ + assert_param(IS_GPIO_ETH_MEDIA_INTERFACE(GPIO_ETH_MediaInterface)); + + /* Configure MII_RMII selection bit */ + *(__IO uint32_t *) MAPR_MII_RMII_SEL_BB = GPIO_ETH_MediaInterface; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c new file mode 100755 index 0000000000..889672683f --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_i2c.c @@ -0,0 +1,1331 @@ +/** + ****************************************************************************** + * @file stm32f10x_i2c.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the I2C firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_i2c.h" +#include "stm32f10x_rcc.h" + + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup I2C + * @brief I2C driver modules + * @{ + */ + +/** @defgroup I2C_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Defines + * @{ + */ + +/* I2C SPE mask */ +#define CR1_PE_Set ((uint16_t)0x0001) +#define CR1_PE_Reset ((uint16_t)0xFFFE) + +/* I2C START mask */ +#define CR1_START_Set ((uint16_t)0x0100) +#define CR1_START_Reset ((uint16_t)0xFEFF) + +/* I2C STOP mask */ +#define CR1_STOP_Set ((uint16_t)0x0200) +#define CR1_STOP_Reset ((uint16_t)0xFDFF) + +/* I2C ACK mask */ +#define CR1_ACK_Set ((uint16_t)0x0400) +#define CR1_ACK_Reset ((uint16_t)0xFBFF) + +/* I2C ENGC mask */ +#define CR1_ENGC_Set ((uint16_t)0x0040) +#define CR1_ENGC_Reset ((uint16_t)0xFFBF) + +/* I2C SWRST mask */ +#define CR1_SWRST_Set ((uint16_t)0x8000) +#define CR1_SWRST_Reset ((uint16_t)0x7FFF) + +/* I2C PEC mask */ +#define CR1_PEC_Set ((uint16_t)0x1000) +#define CR1_PEC_Reset ((uint16_t)0xEFFF) + +/* I2C ENPEC mask */ +#define CR1_ENPEC_Set ((uint16_t)0x0020) +#define CR1_ENPEC_Reset ((uint16_t)0xFFDF) + +/* I2C ENARP mask */ +#define CR1_ENARP_Set ((uint16_t)0x0010) +#define CR1_ENARP_Reset ((uint16_t)0xFFEF) + +/* I2C NOSTRETCH mask */ +#define CR1_NOSTRETCH_Set ((uint16_t)0x0080) +#define CR1_NOSTRETCH_Reset ((uint16_t)0xFF7F) + +/* I2C registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0xFBF5) + +/* I2C DMAEN mask */ +#define CR2_DMAEN_Set ((uint16_t)0x0800) +#define CR2_DMAEN_Reset ((uint16_t)0xF7FF) + +/* I2C LAST mask */ +#define CR2_LAST_Set ((uint16_t)0x1000) +#define CR2_LAST_Reset ((uint16_t)0xEFFF) + +/* I2C FREQ mask */ +#define CR2_FREQ_Reset ((uint16_t)0xFFC0) + +/* I2C ADD0 mask */ +#define OAR1_ADD0_Set ((uint16_t)0x0001) +#define OAR1_ADD0_Reset ((uint16_t)0xFFFE) + +/* I2C ENDUAL mask */ +#define OAR2_ENDUAL_Set ((uint16_t)0x0001) +#define OAR2_ENDUAL_Reset ((uint16_t)0xFFFE) + +/* I2C ADD2 mask */ +#define OAR2_ADD2_Reset ((uint16_t)0xFF01) + +/* I2C F/S mask */ +#define CCR_FS_Set ((uint16_t)0x8000) + +/* I2C CCR mask */ +#define CCR_CCR_Set ((uint16_t)0x0FFF) + +/* I2C FLAG mask */ +#define FLAG_Mask ((uint32_t)0x00FFFFFF) + +/* I2C Interrupt Enable mask */ +#define ITEN_Mask ((uint32_t)0x07000000) + +/** + * @} + */ + +/** @defgroup I2C_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup I2C_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the I2Cx peripheral registers to their default reset values. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval None + */ +void I2C_DeInit(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + if (I2Cx == I2C1) + { + /* Enable I2C1 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, ENABLE); + /* Release I2C1 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C1, DISABLE); + } + else + { + /* Enable I2C2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, ENABLE); + /* Release I2C2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_I2C2, DISABLE); + } +} + +/** + * @brief Initializes the I2Cx peripheral according to the specified + * parameters in the I2C_InitStruct. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_InitStruct: pointer to a I2C_InitTypeDef structure that + * contains the configuration information for the specified I2C peripheral. + * @retval None + */ +void I2C_Init(I2C_TypeDef* I2Cx, I2C_InitTypeDef* I2C_InitStruct) +{ + uint16_t tmpreg = 0, freqrange = 0; + uint16_t result = 0x04; + uint32_t pclk1 = 8000000; + RCC_ClocksTypeDef rcc_clocks; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLOCK_SPEED(I2C_InitStruct->I2C_ClockSpeed)); + assert_param(IS_I2C_MODE(I2C_InitStruct->I2C_Mode)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_InitStruct->I2C_DutyCycle)); + assert_param(IS_I2C_OWN_ADDRESS1(I2C_InitStruct->I2C_OwnAddress1)); + assert_param(IS_I2C_ACK_STATE(I2C_InitStruct->I2C_Ack)); + assert_param(IS_I2C_ACKNOWLEDGE_ADDRESS(I2C_InitStruct->I2C_AcknowledgedAddress)); + +/*---------------------------- I2Cx CR2 Configuration ------------------------*/ + /* Get the I2Cx CR2 value */ + tmpreg = I2Cx->CR2; + /* Clear frequency FREQ[5:0] bits */ + tmpreg &= CR2_FREQ_Reset; + /* Get pclk1 frequency value */ + RCC_GetClocksFreq(&rcc_clocks); + pclk1 = rcc_clocks.PCLK1_Frequency; + /* Set frequency bits depending on pclk1 value */ + freqrange = (uint16_t)(pclk1 / 1000000); + tmpreg |= freqrange; + /* Write to I2Cx CR2 */ + I2Cx->CR2 = tmpreg; + +/*---------------------------- I2Cx CCR Configuration ------------------------*/ + /* Disable the selected I2C peripheral to configure TRISE */ + I2Cx->CR1 &= CR1_PE_Reset; + /* Reset tmpreg value */ + /* Clear F/S, DUTY and CCR[11:0] bits */ + tmpreg = 0; + + /* Configure speed in standard mode */ + if (I2C_InitStruct->I2C_ClockSpeed <= 100000) + { + /* Standard mode speed calculate */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed << 1)); + /* Test if CCR value is under 0x4*/ + if (result < 0x04) + { + /* Set minimum allowed value */ + result = 0x04; + } + /* Set speed value for standard mode */ + tmpreg |= result; + /* Set Maximum Rise Time for standard mode */ + I2Cx->TRISE = freqrange + 1; + } + /* Configure speed in fast mode */ + else /*(I2C_InitStruct->I2C_ClockSpeed <= 400000)*/ + { + if (I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_2) + { + /* Fast mode speed calculate: Tlow/Thigh = 2 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 3)); + } + else /*I2C_InitStruct->I2C_DutyCycle == I2C_DutyCycle_16_9*/ + { + /* Fast mode speed calculate: Tlow/Thigh = 16/9 */ + result = (uint16_t)(pclk1 / (I2C_InitStruct->I2C_ClockSpeed * 25)); + /* Set DUTY bit */ + result |= I2C_DutyCycle_16_9; + } + + /* Test if CCR value is under 0x1*/ + if ((result & CCR_CCR_Set) == 0) + { + /* Set minimum allowed value */ + result |= (uint16_t)0x0001; + } + /* Set speed value and set F/S bit for fast mode */ + tmpreg |= (uint16_t)(result | CCR_FS_Set); + /* Set Maximum Rise Time for fast mode */ + I2Cx->TRISE = (uint16_t)(((freqrange * (uint16_t)300) / (uint16_t)1000) + (uint16_t)1); + } + + /* Write to I2Cx CCR */ + I2Cx->CCR = tmpreg; + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + +/*---------------------------- I2Cx CR1 Configuration ------------------------*/ + /* Get the I2Cx CR1 value */ + tmpreg = I2Cx->CR1; + /* Clear ACK, SMBTYPE and SMBUS bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure I2Cx: mode and acknowledgement */ + /* Set SMBTYPE and SMBUS bits according to I2C_Mode value */ + /* Set ACK bit according to I2C_Ack value */ + tmpreg |= (uint16_t)((uint32_t)I2C_InitStruct->I2C_Mode | I2C_InitStruct->I2C_Ack); + /* Write to I2Cx CR1 */ + I2Cx->CR1 = tmpreg; + +/*---------------------------- I2Cx OAR1 Configuration -----------------------*/ + /* Set I2Cx Own Address1 and acknowledged address */ + I2Cx->OAR1 = (I2C_InitStruct->I2C_AcknowledgedAddress | I2C_InitStruct->I2C_OwnAddress1); +} + +/** + * @brief Fills each I2C_InitStruct member with its default value. + * @param I2C_InitStruct: pointer to an I2C_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2C_StructInit(I2C_InitTypeDef* I2C_InitStruct) +{ +/*---------------- Reset I2C init structure parameters values ----------------*/ + /* initialize the I2C_ClockSpeed member */ + I2C_InitStruct->I2C_ClockSpeed = 5000; + /* Initialize the I2C_Mode member */ + I2C_InitStruct->I2C_Mode = I2C_Mode_I2C; + /* Initialize the I2C_DutyCycle member */ + I2C_InitStruct->I2C_DutyCycle = I2C_DutyCycle_2; + /* Initialize the I2C_OwnAddress1 member */ + I2C_InitStruct->I2C_OwnAddress1 = 0; + /* Initialize the I2C_Ack member */ + I2C_InitStruct->I2C_Ack = I2C_Ack_Disable; + /* Initialize the I2C_AcknowledgedAddress member */ + I2C_InitStruct->I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; +} + +/** + * @brief Enables or disables the specified I2C peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_Cmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C peripheral */ + I2Cx->CR1 |= CR1_PE_Set; + } + else + { + /* Disable the selected I2C peripheral */ + I2Cx->CR1 &= CR1_PE_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C DMA requests. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMACmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C DMA requests */ + I2Cx->CR2 |= CR2_DMAEN_Set; + } + else + { + /* Disable the selected I2C DMA requests */ + I2Cx->CR2 &= CR2_DMAEN_Reset; + } +} + +/** + * @brief Specifies if the next DMA transfer will be the last one. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C DMA last transfer. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DMALastTransferCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Next DMA transfer is the last transfer */ + I2Cx->CR2 |= CR2_LAST_Set; + } + else + { + /* Next DMA transfer is not the last transfer */ + I2Cx->CR2 &= CR2_LAST_Reset; + } +} + +/** + * @brief Generates I2Cx communication START condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C START condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTART(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a START condition */ + I2Cx->CR1 |= CR1_START_Set; + } + else + { + /* Disable the START condition generation */ + I2Cx->CR1 &= CR1_START_Reset; + } +} + +/** + * @brief Generates I2Cx communication STOP condition. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C STOP condition generation. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_GenerateSTOP(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Generate a STOP condition */ + I2Cx->CR1 |= CR1_STOP_Set; + } + else + { + /* Disable the STOP condition generation */ + I2Cx->CR1 &= CR1_STOP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C acknowledge feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C Acknowledgement. + * This parameter can be: ENABLE or DISABLE. + * @retval None. + */ +void I2C_AcknowledgeConfig(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the acknowledgement */ + I2Cx->CR1 |= CR1_ACK_Set; + } + else + { + /* Disable the acknowledgement */ + I2Cx->CR1 &= CR1_ACK_Reset; + } +} + +/** + * @brief Configures the specified I2C own address2. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the 7bit I2C own address2. + * @retval None. + */ +void I2C_OwnAddress2Config(I2C_TypeDef* I2Cx, uint8_t Address) +{ + uint16_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Get the old register value */ + tmpreg = I2Cx->OAR2; + + /* Reset I2Cx Own address2 bit [7:1] */ + tmpreg &= OAR2_ADD2_Reset; + + /* Set I2Cx Own address2 */ + tmpreg |= (uint16_t)((uint16_t)Address & (uint16_t)0x00FE); + + /* Store the new register value */ + I2Cx->OAR2 = tmpreg; +} + +/** + * @brief Enables or disables the specified I2C dual addressing mode. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C dual addressing mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_DualAddressCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable dual addressing mode */ + I2Cx->OAR2 |= OAR2_ENDUAL_Set; + } + else + { + /* Disable dual addressing mode */ + I2Cx->OAR2 &= OAR2_ENDUAL_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C general call feature. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C General call. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_GeneralCallCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable generall call */ + I2Cx->CR1 |= CR1_ENGC_Set; + } + else + { + /* Disable generall call */ + I2Cx->CR1 &= CR1_ENGC_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C interrupts. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the I2C interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg I2C_IT_BUF: Buffer interrupt mask + * @arg I2C_IT_EVT: Event interrupt mask + * @arg I2C_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified I2C interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ITConfig(I2C_TypeDef* I2Cx, uint16_t I2C_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_I2C_CONFIG_IT(I2C_IT)); + + if (NewState != DISABLE) + { + /* Enable the selected I2C interrupts */ + I2Cx->CR2 |= I2C_IT; + } + else + { + /* Disable the selected I2C interrupts */ + I2Cx->CR2 &= (uint16_t)~I2C_IT; + } +} + +/** + * @brief Sends a data byte through the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Data: Byte to be transmitted.. + * @retval None + */ +void I2C_SendData(I2C_TypeDef* I2Cx, uint8_t Data) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Write in the DR register the data to be sent */ + I2Cx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the I2Cx peripheral. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The value of the received data. + */ +uint8_t I2C_ReceiveData(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the data in the DR register */ + return (uint8_t)I2Cx->DR; +} + +/** + * @brief Transmits the address byte to select the slave device. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param Address: specifies the slave address which will be transmitted + * @param I2C_Direction: specifies whether the I2C device will be a + * Transmitter or a Receiver. This parameter can be one of the following values + * @arg I2C_Direction_Transmitter: Transmitter mode + * @arg I2C_Direction_Receiver: Receiver mode + * @retval None. + */ +void I2C_Send7bitAddress(I2C_TypeDef* I2Cx, uint8_t Address, uint8_t I2C_Direction) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DIRECTION(I2C_Direction)); + /* Test on the direction to set/reset the read/write bit */ + if (I2C_Direction != I2C_Direction_Transmitter) + { + /* Set the address bit0 for read */ + Address |= OAR1_ADD0_Set; + } + else + { + /* Reset the address bit0 for write */ + Address &= OAR1_ADD0_Reset; + } + /* Send the address */ + I2Cx->DR = Address; +} + +/** + * @brief Reads the specified I2C register and returns its value. + * @param I2C_Register: specifies the register to read. + * This parameter can be one of the following values: + * @arg I2C_Register_CR1: CR1 register. + * @arg I2C_Register_CR2: CR2 register. + * @arg I2C_Register_OAR1: OAR1 register. + * @arg I2C_Register_OAR2: OAR2 register. + * @arg I2C_Register_DR: DR register. + * @arg I2C_Register_SR1: SR1 register. + * @arg I2C_Register_SR2: SR2 register. + * @arg I2C_Register_CCR: CCR register. + * @arg I2C_Register_TRISE: TRISE register. + * @retval The value of the read register. + */ +uint16_t I2C_ReadRegister(I2C_TypeDef* I2Cx, uint8_t I2C_Register) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_REGISTER(I2C_Register)); + + tmp = (uint32_t) I2Cx; + tmp += I2C_Register; + + /* Return the selected register value */ + return (*(__IO uint16_t *) tmp); +} + +/** + * @brief Enables or disables the specified I2C software reset. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C software reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_SoftwareResetCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Peripheral under reset */ + I2Cx->CR1 |= CR1_SWRST_Set; + } + else + { + /* Peripheral not under reset */ + I2Cx->CR1 &= CR1_SWRST_Reset; + } +} + +/** + * @brief Selects the specified I2C NACK position in master receiver mode. + * This function is useful in I2C Master Receiver mode when the number + * of data to be received is equal to 2. In this case, this function + * should be called (with parameter I2C_NACKPosition_Next) before data + * reception starts,as described in the 2-byte reception procedure + * recommended in Reference Manual in Section: Master receiver. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_NACKPosition: specifies the NACK position. + * This parameter can be one of the following values: + * @arg I2C_NACKPosition_Next: indicates that the next byte will be the last + * received byte. + * @arg I2C_NACKPosition_Current: indicates that current byte is the last + * received byte. + * + * @note This function configures the same bit (POS) as I2C_PECPositionConfig() + * but is intended to be used in I2C mode while I2C_PECPositionConfig() + * is intended to used in SMBUS mode. + * + * @retval None + */ +void I2C_NACKPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_NACKPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_NACK_POSITION(I2C_NACKPosition)); + + /* Check the input parameter */ + if (I2C_NACKPosition == I2C_NACKPosition_Next) + { + /* Next byte in shift register is the last received byte */ + I2Cx->CR1 |= I2C_NACKPosition_Next; + } + else + { + /* Current byte in shift register is the last received byte */ + I2Cx->CR1 &= I2C_NACKPosition_Current; + } +} + +/** + * @brief Drives the SMBusAlert pin high or low for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_SMBusAlert: specifies SMBAlert pin level. + * This parameter can be one of the following values: + * @arg I2C_SMBusAlert_Low: SMBAlert pin driven low + * @arg I2C_SMBusAlert_High: SMBAlert pin driven high + * @retval None + */ +void I2C_SMBusAlertConfig(I2C_TypeDef* I2Cx, uint16_t I2C_SMBusAlert) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_SMBUS_ALERT(I2C_SMBusAlert)); + if (I2C_SMBusAlert == I2C_SMBusAlert_Low) + { + /* Drive the SMBusAlert pin Low */ + I2Cx->CR1 |= I2C_SMBusAlert_Low; + } + else + { + /* Drive the SMBusAlert pin High */ + I2Cx->CR1 &= I2C_SMBusAlert_High; + } +} + +/** + * @brief Enables or disables the specified I2C PEC transfer. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2C PEC transmission. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_TransmitPEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC transmission */ + I2Cx->CR1 |= CR1_PEC_Set; + } + else + { + /* Disable the selected I2C PEC transmission */ + I2Cx->CR1 &= CR1_PEC_Reset; + } +} + +/** + * @brief Selects the specified I2C PEC position. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_PECPosition: specifies the PEC position. + * This parameter can be one of the following values: + * @arg I2C_PECPosition_Next: indicates that the next byte is PEC + * @arg I2C_PECPosition_Current: indicates that current byte is PEC + * + * @note This function configures the same bit (POS) as I2C_NACKPositionConfig() + * but is intended to be used in SMBUS mode while I2C_NACKPositionConfig() + * is intended to used in I2C mode. + * + * @retval None + */ +void I2C_PECPositionConfig(I2C_TypeDef* I2Cx, uint16_t I2C_PECPosition) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_PEC_POSITION(I2C_PECPosition)); + if (I2C_PECPosition == I2C_PECPosition_Next) + { + /* Next byte in shift register is PEC */ + I2Cx->CR1 |= I2C_PECPosition_Next; + } + else + { + /* Current byte in shift register is PEC */ + I2Cx->CR1 &= I2C_PECPosition_Current; + } +} + +/** + * @brief Enables or disables the PEC value calculation of the transferred bytes. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx PEC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_CalculatePEC(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C PEC calculation */ + I2Cx->CR1 |= CR1_ENPEC_Set; + } + else + { + /* Disable the selected I2C PEC calculation */ + I2Cx->CR1 &= CR1_ENPEC_Reset; + } +} + +/** + * @brief Returns the PEC value for the specified I2C. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @retval The PEC value. + */ +uint8_t I2C_GetPEC(I2C_TypeDef* I2Cx) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + /* Return the selected I2C PEC value */ + return ((I2Cx->SR2) >> 8); +} + +/** + * @brief Enables or disables the specified I2C ARP. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx ARP. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_ARPCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected I2C ARP */ + I2Cx->CR1 |= CR1_ENARP_Set; + } + else + { + /* Disable the selected I2C ARP */ + I2Cx->CR1 &= CR1_ENARP_Reset; + } +} + +/** + * @brief Enables or disables the specified I2C Clock stretching. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param NewState: new state of the I2Cx Clock stretching. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2C_StretchClockCmd(I2C_TypeDef* I2Cx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState == DISABLE) + { + /* Enable the selected I2C Clock stretching */ + I2Cx->CR1 |= CR1_NOSTRETCH_Set; + } + else + { + /* Disable the selected I2C Clock stretching */ + I2Cx->CR1 &= CR1_NOSTRETCH_Reset; + } +} + +/** + * @brief Selects the specified I2C fast mode duty cycle. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_DutyCycle: specifies the fast mode duty cycle. + * This parameter can be one of the following values: + * @arg I2C_DutyCycle_2: I2C fast mode Tlow/Thigh = 2 + * @arg I2C_DutyCycle_16_9: I2C fast mode Tlow/Thigh = 16/9 + * @retval None + */ +void I2C_FastModeDutyCycleConfig(I2C_TypeDef* I2Cx, uint16_t I2C_DutyCycle) +{ + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_DUTY_CYCLE(I2C_DutyCycle)); + if (I2C_DutyCycle != I2C_DutyCycle_16_9) + { + /* I2C fast mode Tlow/Thigh=2 */ + I2Cx->CCR &= I2C_DutyCycle_2; + } + else + { + /* I2C fast mode Tlow/Thigh=16/9 */ + I2Cx->CCR |= I2C_DutyCycle_16_9; + } +} + + + +/** + * @brief + **************************************************************************************** + * + * I2C State Monitoring Functions + * + **************************************************************************************** + * This I2C driver provides three different ways for I2C state monitoring + * depending on the application requirements and constraints: + * + * + * 1) Basic state monitoring: + * Using I2C_CheckEvent() function: + * It compares the status registers (SR1 and SR2) content to a given event + * (can be the combination of one or more flags). + * It returns SUCCESS if the current status includes the given flags + * and returns ERROR if one or more flags are missing in the current status. + * - When to use: + * - This function is suitable for most applications as well as for startup + * activity since the events are fully described in the product reference manual + * (RM0008). + * - It is also suitable for users who need to define their own events. + * - Limitations: + * - If an error occurs (ie. error flags are set besides to the monitored flags), + * the I2C_CheckEvent() function may return SUCCESS despite the communication + * hold or corrupted real state. + * In this case, it is advised to use error interrupts to monitor the error + * events and handle them in the interrupt IRQ handler. + * + * @note + * For error management, it is advised to use the following functions: + * - I2C_ITConfig() to configure and enable the error interrupts (I2C_IT_ERR). + * - I2Cx_ER_IRQHandler() which is called when the error interrupt occurs. + * Where x is the peripheral instance (I2C1, I2C2 ...) + * - I2C_GetFlagStatus() or I2C_GetITStatus() to be called into I2Cx_ER_IRQHandler() + * in order to determine which error occured. + * - I2C_ClearFlag() or I2C_ClearITPendingBit() and/or I2C_SoftwareResetCmd() + * and/or I2C_GenerateStop() in order to clear the error flag and source, + * and return to correct communication status. + * + * + * 2) Advanced state monitoring: + * Using the function I2C_GetLastEvent() which returns the image of both status + * registers in a single word (uint32_t) (Status Register 2 value is shifted left + * by 16 bits and concatenated to Status Register 1). + * - When to use: + * - This function is suitable for the same applications above but it allows to + * overcome the mentioned limitation of I2C_GetFlagStatus() function. + * The returned value could be compared to events already defined in the + * library (stm32f10x_i2c.h) or to custom values defined by user. + * - This function is suitable when multiple flags are monitored at the same time. + * - At the opposite of I2C_CheckEvent() function, this function allows user to + * choose when an event is accepted (when all events flags are set and no + * other flags are set or just when the needed flags are set like + * I2C_CheckEvent() function). + * - Limitations: + * - User may need to define his own events. + * - Same remark concerning the error management is applicable for this + * function if user decides to check only regular communication flags (and + * ignores error flags). + * + * + * 3) Flag-based state monitoring: + * Using the function I2C_GetFlagStatus() which simply returns the status of + * one single flag (ie. I2C_FLAG_RXNE ...). + * - When to use: + * - This function could be used for specific applications or in debug phase. + * - It is suitable when only one flag checking is needed (most I2C events + * are monitored through multiple flags). + * - Limitations: + * - When calling this function, the Status register is accessed. Some flags are + * cleared when the status register is accessed. So checking the status + * of one Flag, may clear other ones. + * - Function may need to be called twice or more in order to monitor one + * single event. + * + * For detailed description of Events, please refer to section I2C_Events in + * stm32f10x_i2c.h file. + * + */ + +/** + * + * 1) Basic state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the last I2Cx Event is equal to the one passed + * as parameter. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_EVENT: specifies the event to be checked. + * This parameter can be one of the following values: + * @arg I2C_EVENT_SLAVE_TRANSMITTER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_ADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_TRANSMITTER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_RECEIVER_SECONDADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_GENERALCALLADDRESS_MATCHED : EV1 + * @arg I2C_EVENT_SLAVE_BYTE_RECEIVED : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_DUALF) : EV2 + * @arg (I2C_EVENT_SLAVE_BYTE_RECEIVED | I2C_FLAG_GENCALL) : EV2 + * @arg I2C_EVENT_SLAVE_BYTE_TRANSMITTED : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_DUALF) : EV3 + * @arg (I2C_EVENT_SLAVE_BYTE_TRANSMITTED | I2C_FLAG_GENCALL) : EV3 + * @arg I2C_EVENT_SLAVE_ACK_FAILURE : EV3_2 + * @arg I2C_EVENT_SLAVE_STOP_DETECTED : EV4 + * @arg I2C_EVENT_MASTER_MODE_SELECT : EV5 + * @arg I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED : EV6 + * @arg I2C_EVENT_MASTER_BYTE_RECEIVED : EV7 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTING : EV8 + * @arg I2C_EVENT_MASTER_BYTE_TRANSMITTED : EV8_2 + * @arg I2C_EVENT_MASTER_MODE_ADDRESS10 : EV9 + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval An ErrorStatus enumeration value: + * - SUCCESS: Last event is equal to the I2C_EVENT + * - ERROR: Last event is different from the I2C_EVENT + */ +ErrorStatus I2C_CheckEvent(I2C_TypeDef* I2Cx, uint32_t I2C_EVENT) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + ErrorStatus status = ERROR; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_EVENT(I2C_EVENT)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Check whether the last event contains the I2C_EVENT */ + if ((lastevent & I2C_EVENT) == I2C_EVENT) + { + /* SUCCESS: last event is equal to I2C_EVENT */ + status = SUCCESS; + } + else + { + /* ERROR: last event is different from I2C_EVENT */ + status = ERROR; + } + /* Return status */ + return status; +} + +/** + * + * 2) Advanced state monitoring + ******************************************************************************* + */ + +/** + * @brief Returns the last I2Cx Event. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * + * @note: For detailed description of Events, please refer to section + * I2C_Events in stm32f10x_i2c.h file. + * + * @retval The last event + */ +uint32_t I2C_GetLastEvent(I2C_TypeDef* I2Cx) +{ + uint32_t lastevent = 0; + uint32_t flag1 = 0, flag2 = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + + /* Read the I2Cx status register */ + flag1 = I2Cx->SR1; + flag2 = I2Cx->SR2; + flag2 = flag2 << 16; + + /* Get the last event value from I2C status register */ + lastevent = (flag1 | flag2) & FLAG_Mask; + + /* Return status */ + return lastevent; +} + +/** + * + * 3) Flag-based state monitoring + ******************************************************************************* + */ + +/** + * @brief Checks whether the specified I2C flag is set or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg I2C_FLAG_DUALF: Dual flag (Slave mode) + * @arg I2C_FLAG_SMBHOST: SMBus host header (Slave mode) + * @arg I2C_FLAG_SMBDEFAULT: SMBus default header (Slave mode) + * @arg I2C_FLAG_GENCALL: General call header flag (Slave mode) + * @arg I2C_FLAG_TRA: Transmitter/Receiver flag + * @arg I2C_FLAG_BUSY: Bus busy flag + * @arg I2C_FLAG_MSL: Master/Slave flag + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * @arg I2C_FLAG_TXE: Data register empty flag (Transmitter) + * @arg I2C_FLAG_RXNE: Data register not empty (Receiver) flag + * @arg I2C_FLAG_STOPF: Stop detection flag (Slave mode) + * @arg I2C_FLAG_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_FLAG_BTF: Byte transfer finished flag + * @arg I2C_FLAG_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDA" + * @arg I2C_FLAG_SB: Start bit flag (Master mode) + * @retval The new state of I2C_FLAG (SET or RESET). + */ +FlagStatus I2C_GetFlagStatus(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + FlagStatus bitstatus = RESET; + __IO uint32_t i2creg = 0, i2cxbase = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_FLAG(I2C_FLAG)); + + /* Get the I2Cx peripheral base address */ + i2cxbase = (uint32_t)I2Cx; + + /* Read flag register index */ + i2creg = I2C_FLAG >> 28; + + /* Get bit[23:0] of the flag */ + I2C_FLAG &= FLAG_Mask; + + if(i2creg != 0) + { + /* Get the I2Cx SR1 register address */ + i2cxbase += 0x14; + } + else + { + /* Flag in I2Cx SR2 Register */ + I2C_FLAG = (uint32_t)(I2C_FLAG >> 16); + /* Get the I2Cx SR2 register address */ + i2cxbase += 0x18; + } + + if(((*(__IO uint32_t *)i2cxbase) & I2C_FLAG) != (uint32_t)RESET) + { + /* I2C_FLAG is set */ + bitstatus = SET; + } + else + { + /* I2C_FLAG is reset */ + bitstatus = RESET; + } + + /* Return the I2C_FLAG status */ + return bitstatus; +} + + + +/** + * @brief Clears the I2Cx's pending flags. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg I2C_FLAG_SMBALERT: SMBus Alert flag + * @arg I2C_FLAG_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_FLAG_PECERR: PEC error in reception flag + * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_FLAG_AF: Acknowledge failure flag + * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_FLAG_BERR: Bus error flag + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetFlagStatus()) followed by a write operation + * to I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetFlagStatus()) followed by writing the + * second byte of the address in DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetFlagStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetFlagStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared software sequence: a read operation to I2C_SR1 + * register (I2C_GetFlagStatus()) followed by a write operation to I2C_DR + * register (I2C_SendData()). + * @retval None + */ +void I2C_ClearFlag(I2C_TypeDef* I2Cx, uint32_t I2C_FLAG) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_FLAG(I2C_FLAG)); + /* Get the I2C flag position */ + flagpos = I2C_FLAG & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @brief Checks whether the specified I2C interrupt has occurred or not. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt source to check. + * This parameter can be one of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert flag + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error flag + * @arg I2C_IT_PECERR: PEC error in reception flag + * @arg I2C_IT_OVR: Overrun/Underrun flag (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure flag + * @arg I2C_IT_ARLO: Arbitration lost flag (Master mode) + * @arg I2C_IT_BERR: Bus error flag + * @arg I2C_IT_TXE: Data register empty flag (Transmitter) + * @arg I2C_IT_RXNE: Data register not empty (Receiver) flag + * @arg I2C_IT_STOPF: Stop detection flag (Slave mode) + * @arg I2C_IT_ADD10: 10-bit header sent flag (Master mode) + * @arg I2C_IT_BTF: Byte transfer finished flag + * @arg I2C_IT_ADDR: Address sent flag (Master mode) "ADSL" + * Address matched flag (Slave mode)"ENDAD" + * @arg I2C_IT_SB: Start bit flag (Master mode) + * @retval The new state of I2C_IT (SET or RESET). + */ +ITStatus I2C_GetITStatus(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + ITStatus bitstatus = RESET; + uint32_t enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_GET_IT(I2C_IT)); + + /* Check if the interrupt source is enabled or not */ + enablestatus = (uint32_t)(((I2C_IT & ITEN_Mask) >> 16) & (I2Cx->CR2)) ; + + /* Get bit[23:0] of the flag */ + I2C_IT &= FLAG_Mask; + + /* Check the status of the specified I2C flag */ + if (((I2Cx->SR1 & I2C_IT) != (uint32_t)RESET) && enablestatus) + { + /* I2C_IT is set */ + bitstatus = SET; + } + else + { + /* I2C_IT is reset */ + bitstatus = RESET; + } + /* Return the I2C_IT status */ + return bitstatus; +} + +/** + * @brief Clears the I2Cx’s interrupt pending bits. + * @param I2Cx: where x can be 1 or 2 to select the I2C peripheral. + * @param I2C_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg I2C_IT_SMBALERT: SMBus Alert interrupt + * @arg I2C_IT_TIMEOUT: Timeout or Tlow error interrupt + * @arg I2C_IT_PECERR: PEC error in reception interrupt + * @arg I2C_IT_OVR: Overrun/Underrun interrupt (Slave mode) + * @arg I2C_IT_AF: Acknowledge failure interrupt + * @arg I2C_IT_ARLO: Arbitration lost interrupt (Master mode) + * @arg I2C_IT_BERR: Bus error interrupt + * + * @note + * - STOPF (STOP detection) is cleared by software sequence: a read operation + * to I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_CR1 register (I2C_Cmd() to re-enable the I2C peripheral). + * - ADD10 (10-bit header sent) is cleared by software sequence: a read + * operation to I2C_SR1 (I2C_GetITStatus()) followed by writing the second + * byte of the address in I2C_DR register. + * - BTF (Byte Transfer Finished) is cleared by software sequence: a read + * operation to I2C_SR1 register (I2C_GetITStatus()) followed by a + * read/write to I2C_DR register (I2C_SendData()). + * - ADDR (Address sent) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a read operation to + * I2C_SR2 register ((void)(I2Cx->SR2)). + * - SB (Start Bit) is cleared by software sequence: a read operation to + * I2C_SR1 register (I2C_GetITStatus()) followed by a write operation to + * I2C_DR register (I2C_SendData()). + * @retval None + */ +void I2C_ClearITPendingBit(I2C_TypeDef* I2Cx, uint32_t I2C_IT) +{ + uint32_t flagpos = 0; + /* Check the parameters */ + assert_param(IS_I2C_ALL_PERIPH(I2Cx)); + assert_param(IS_I2C_CLEAR_IT(I2C_IT)); + /* Get the I2C flag position */ + flagpos = I2C_IT & FLAG_Mask; + /* Clear the selected I2C flag */ + I2Cx->SR1 = (uint16_t)~flagpos; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c new file mode 100755 index 0000000000..9d3b0e855a --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_iwdg.c @@ -0,0 +1,190 @@ +/** + ****************************************************************************** + * @file stm32f10x_iwdg.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the IWDG firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_iwdg.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup IWDG + * @brief IWDG driver modules + * @{ + */ + +/** @defgroup IWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Defines + * @{ + */ + +/* ---------------------- IWDG registers bit mask ----------------------------*/ + +/* KR register bit mask */ +#define KR_KEY_Reload ((uint16_t)0xAAAA) +#define KR_KEY_Enable ((uint16_t)0xCCCC) + +/** + * @} + */ + +/** @defgroup IWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup IWDG_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables write access to IWDG_PR and IWDG_RLR registers. + * @param IWDG_WriteAccess: new state of write access to IWDG_PR and IWDG_RLR registers. + * This parameter can be one of the following values: + * @arg IWDG_WriteAccess_Enable: Enable write access to IWDG_PR and IWDG_RLR registers + * @arg IWDG_WriteAccess_Disable: Disable write access to IWDG_PR and IWDG_RLR registers + * @retval None + */ +void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess) +{ + /* Check the parameters */ + assert_param(IS_IWDG_WRITE_ACCESS(IWDG_WriteAccess)); + IWDG->KR = IWDG_WriteAccess; +} + +/** + * @brief Sets IWDG Prescaler value. + * @param IWDG_Prescaler: specifies the IWDG Prescaler value. + * This parameter can be one of the following values: + * @arg IWDG_Prescaler_4: IWDG prescaler set to 4 + * @arg IWDG_Prescaler_8: IWDG prescaler set to 8 + * @arg IWDG_Prescaler_16: IWDG prescaler set to 16 + * @arg IWDG_Prescaler_32: IWDG prescaler set to 32 + * @arg IWDG_Prescaler_64: IWDG prescaler set to 64 + * @arg IWDG_Prescaler_128: IWDG prescaler set to 128 + * @arg IWDG_Prescaler_256: IWDG prescaler set to 256 + * @retval None + */ +void IWDG_SetPrescaler(uint8_t IWDG_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_IWDG_PRESCALER(IWDG_Prescaler)); + IWDG->PR = IWDG_Prescaler; +} + +/** + * @brief Sets IWDG Reload value. + * @param Reload: specifies the IWDG Reload value. + * This parameter must be a number between 0 and 0x0FFF. + * @retval None + */ +void IWDG_SetReload(uint16_t Reload) +{ + /* Check the parameters */ + assert_param(IS_IWDG_RELOAD(Reload)); + IWDG->RLR = Reload; +} + +/** + * @brief Reloads IWDG counter with value defined in the reload register + * (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_ReloadCounter(void) +{ + IWDG->KR = KR_KEY_Reload; +} + +/** + * @brief Enables IWDG (write access to IWDG_PR and IWDG_RLR registers disabled). + * @param None + * @retval None + */ +void IWDG_Enable(void) +{ + IWDG->KR = KR_KEY_Enable; +} + +/** + * @brief Checks whether the specified IWDG flag is set or not. + * @param IWDG_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg IWDG_FLAG_PVU: Prescaler Value Update on going + * @arg IWDG_FLAG_RVU: Reload Value Update on going + * @retval The new state of IWDG_FLAG (SET or RESET). + */ +FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_IWDG_FLAG(IWDG_FLAG)); + if ((IWDG->SR & IWDG_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c new file mode 100755 index 0000000000..147bf0f8d6 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_pwr.c @@ -0,0 +1,307 @@ +/** + ****************************************************************************** + * @file stm32f10x_pwr.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the PWR firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_pwr.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup PWR + * @brief PWR driver modules + * @{ + */ + +/** @defgroup PWR_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Defines + * @{ + */ + +/* --------- PWR registers bit address in the alias region ---------- */ +#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of DBP bit */ +#define CR_OFFSET (PWR_OFFSET + 0x00) +#define DBP_BitNumber 0x08 +#define CR_DBP_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (DBP_BitNumber * 4)) + +/* Alias word address of PVDE bit */ +#define PVDE_BitNumber 0x04 +#define CR_PVDE_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PVDE_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of EWUP bit */ +#define CSR_OFFSET (PWR_OFFSET + 0x04) +#define EWUP_BitNumber 0x08 +#define CSR_EWUP_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (EWUP_BitNumber * 4)) + +/* ------------------ PWR registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_DS_MASK ((uint32_t)0xFFFFFFFC) +#define CR_PLS_MASK ((uint32_t)0xFFFFFF1F) + + +/** + * @} + */ + +/** @defgroup PWR_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup PWR_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the PWR peripheral registers to their default reset values. + * @param None + * @retval None + */ +void PWR_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_PWR, DISABLE); +} + +/** + * @brief Enables or disables access to the RTC and backup registers. + * @param NewState: new state of the access to the RTC and backup registers. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_BackupAccessCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_DBP_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Power Voltage Detector(PVD). + * @param NewState: new state of the PVD. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_PVDCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PVDE_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the voltage threshold detected by the Power Voltage Detector(PVD). + * @param PWR_PVDLevel: specifies the PVD detection level + * This parameter can be one of the following values: + * @arg PWR_PVDLevel_2V2: PVD detection level set to 2.2V + * @arg PWR_PVDLevel_2V3: PVD detection level set to 2.3V + * @arg PWR_PVDLevel_2V4: PVD detection level set to 2.4V + * @arg PWR_PVDLevel_2V5: PVD detection level set to 2.5V + * @arg PWR_PVDLevel_2V6: PVD detection level set to 2.6V + * @arg PWR_PVDLevel_2V7: PVD detection level set to 2.7V + * @arg PWR_PVDLevel_2V8: PVD detection level set to 2.8V + * @arg PWR_PVDLevel_2V9: PVD detection level set to 2.9V + * @retval None + */ +void PWR_PVDLevelConfig(uint32_t PWR_PVDLevel) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_PVD_LEVEL(PWR_PVDLevel)); + tmpreg = PWR->CR; + /* Clear PLS[7:5] bits */ + tmpreg &= CR_PLS_MASK; + /* Set PLS[7:5] bits according to PWR_PVDLevel value */ + tmpreg |= PWR_PVDLevel; + /* Store the new value */ + PWR->CR = tmpreg; +} + +/** + * @brief Enables or disables the WakeUp Pin functionality. + * @param NewState: new state of the WakeUp Pin functionality. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void PWR_WakeUpPinCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_EWUP_BB = (uint32_t)NewState; +} + +/** + * @brief Enters STOP mode. + * @param PWR_Regulator: specifies the regulator state in STOP mode. + * This parameter can be one of the following values: + * @arg PWR_Regulator_ON: STOP mode with regulator ON + * @arg PWR_Regulator_LowPower: STOP mode with regulator in low power mode + * @param PWR_STOPEntry: specifies if STOP mode in entered with WFI or WFE instruction. + * This parameter can be one of the following values: + * @arg PWR_STOPEntry_WFI: enter STOP mode with WFI instruction + * @arg PWR_STOPEntry_WFE: enter STOP mode with WFE instruction + * @retval None + */ +void PWR_EnterSTOPMode(uint32_t PWR_Regulator, uint8_t PWR_STOPEntry) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_PWR_REGULATOR(PWR_Regulator)); + assert_param(IS_PWR_STOP_ENTRY(PWR_STOPEntry)); + + /* Select the regulator state in STOP mode ---------------------------------*/ + tmpreg = PWR->CR; + /* Clear PDDS and LPDS bits */ + tmpreg &= CR_DS_MASK; + /* Set LPDS bit according to PWR_Regulator value */ + tmpreg |= PWR_Regulator; + /* Store the new value */ + PWR->CR = tmpreg; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; + + /* Select STOP mode entry --------------------------------------------------*/ + if(PWR_STOPEntry == PWR_STOPEntry_WFI) + { + /* Request Wait For Interrupt */ + __WFI(); + } + else + { + /* Request Wait For Event */ + __WFE(); + } + + /* Reset SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR &= (uint32_t)~((uint32_t)SCB_SCR_SLEEPDEEP); +} + +/** + * @brief Enters STANDBY mode. + * @param None + * @retval None + */ +void PWR_EnterSTANDBYMode(void) +{ + /* Clear Wake-up flag */ + PWR->CR |= PWR_CR_CWUF; + /* Select STANDBY mode */ + PWR->CR |= PWR_CR_PDDS; + /* Set SLEEPDEEP bit of Cortex System Control Register */ + SCB->SCR |= SCB_SCR_SLEEPDEEP; +/* This option is used to ensure that store operations are completed */ +#if defined ( __CC_ARM ) + __force_stores(); +#endif + /* Request Wait For Interrupt */ + __WFI(); +} + +/** + * @brief Checks whether the specified PWR flag is set or not. + * @param PWR_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @arg PWR_FLAG_PVDO: PVD Output + * @retval The new state of PWR_FLAG (SET or RESET). + */ +FlagStatus PWR_GetFlagStatus(uint32_t PWR_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_PWR_GET_FLAG(PWR_FLAG)); + + if ((PWR->CSR & PWR_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the PWR's pending flags. + * @param PWR_FLAG: specifies the flag to clear. + * This parameter can be one of the following values: + * @arg PWR_FLAG_WU: Wake Up flag + * @arg PWR_FLAG_SB: StandBy flag + * @retval None + */ +void PWR_ClearFlag(uint32_t PWR_FLAG) +{ + /* Check the parameters */ + assert_param(IS_PWR_CLEAR_FLAG(PWR_FLAG)); + + PWR->CR |= PWR_FLAG << 2; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c new file mode 100755 index 0000000000..4b2ec1f104 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c @@ -0,0 +1,1470 @@ +/** + ****************************************************************************** + * @file stm32f10x_rcc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the RCC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RCC + * @brief RCC driver modules + * @{ + */ + +/** @defgroup RCC_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Defines + * @{ + */ + +/* ------------ RCC registers bit address in the alias region ----------- */ +#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) + +/* --- CR Register ---*/ + +/* Alias word address of HSION bit */ +#define CR_OFFSET (RCC_OFFSET + 0x00) +#define HSION_BitNumber 0x00 +#define CR_HSION_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (HSION_BitNumber * 4)) + +/* Alias word address of PLLON bit */ +#define PLLON_BitNumber 0x18 +#define CR_PLLON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLLON_BitNumber * 4)) + +#ifdef STM32F10X_CL + /* Alias word address of PLL2ON bit */ + #define PLL2ON_BitNumber 0x1A + #define CR_PLL2ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL2ON_BitNumber * 4)) + + /* Alias word address of PLL3ON bit */ + #define PLL3ON_BitNumber 0x1C + #define CR_PLL3ON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (PLL3ON_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* Alias word address of CSSON bit */ +#define CSSON_BitNumber 0x13 +#define CR_CSSON_BB (PERIPH_BB_BASE + (CR_OFFSET * 32) + (CSSON_BitNumber * 4)) + +/* --- CFGR Register ---*/ + +/* Alias word address of USBPRE bit */ +#define CFGR_OFFSET (RCC_OFFSET + 0x04) + +#ifndef STM32F10X_CL + #define USBPRE_BitNumber 0x16 + #define CFGR_USBPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (USBPRE_BitNumber * 4)) +#else + #define OTGFSPRE_BitNumber 0x16 + #define CFGR_OTGFSPRE_BB (PERIPH_BB_BASE + (CFGR_OFFSET * 32) + (OTGFSPRE_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* --- BDCR Register ---*/ + +/* Alias word address of RTCEN bit */ +#define BDCR_OFFSET (RCC_OFFSET + 0x20) +#define RTCEN_BitNumber 0x0F +#define BDCR_RTCEN_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (RTCEN_BitNumber * 4)) + +/* Alias word address of BDRST bit */ +#define BDRST_BitNumber 0x10 +#define BDCR_BDRST_BB (PERIPH_BB_BASE + (BDCR_OFFSET * 32) + (BDRST_BitNumber * 4)) + +/* --- CSR Register ---*/ + +/* Alias word address of LSION bit */ +#define CSR_OFFSET (RCC_OFFSET + 0x24) +#define LSION_BitNumber 0x00 +#define CSR_LSION_BB (PERIPH_BB_BASE + (CSR_OFFSET * 32) + (LSION_BitNumber * 4)) + +#ifdef STM32F10X_CL +/* --- CFGR2 Register ---*/ + + /* Alias word address of I2S2SRC bit */ + #define CFGR2_OFFSET (RCC_OFFSET + 0x2C) + #define I2S2SRC_BitNumber 0x11 + #define CFGR2_I2S2SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S2SRC_BitNumber * 4)) + + /* Alias word address of I2S3SRC bit */ + #define I2S3SRC_BitNumber 0x12 + #define CFGR2_I2S3SRC_BB (PERIPH_BB_BASE + (CFGR2_OFFSET * 32) + (I2S3SRC_BitNumber * 4)) +#endif /* STM32F10X_CL */ + +/* ---------------------- RCC registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_HSEBYP_Reset ((uint32_t)0xFFFBFFFF) +#define CR_HSEBYP_Set ((uint32_t)0x00040000) +#define CR_HSEON_Reset ((uint32_t)0xFFFEFFFF) +#define CR_HSEON_Set ((uint32_t)0x00010000) +#define CR_HSITRIM_Mask ((uint32_t)0xFFFFFF07) + +/* CFGR register bit mask */ +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) + #define CFGR_PLL_Mask ((uint32_t)0xFFC2FFFF) +#else + #define CFGR_PLL_Mask ((uint32_t)0xFFC0FFFF) +#endif /* STM32F10X_CL */ + +#define CFGR_PLLMull_Mask ((uint32_t)0x003C0000) +#define CFGR_PLLSRC_Mask ((uint32_t)0x00010000) +#define CFGR_PLLXTPRE_Mask ((uint32_t)0x00020000) +#define CFGR_SWS_Mask ((uint32_t)0x0000000C) +#define CFGR_SW_Mask ((uint32_t)0xFFFFFFFC) +#define CFGR_HPRE_Reset_Mask ((uint32_t)0xFFFFFF0F) +#define CFGR_HPRE_Set_Mask ((uint32_t)0x000000F0) +#define CFGR_PPRE1_Reset_Mask ((uint32_t)0xFFFFF8FF) +#define CFGR_PPRE1_Set_Mask ((uint32_t)0x00000700) +#define CFGR_PPRE2_Reset_Mask ((uint32_t)0xFFFFC7FF) +#define CFGR_PPRE2_Set_Mask ((uint32_t)0x00003800) +#define CFGR_ADCPRE_Reset_Mask ((uint32_t)0xFFFF3FFF) +#define CFGR_ADCPRE_Set_Mask ((uint32_t)0x0000C000) + +/* CSR register bit mask */ +#define CSR_RMVF_Set ((uint32_t)0x01000000) + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/* CFGR2 register bit mask */ + #define CFGR2_PREDIV1SRC ((uint32_t)0x00010000) + #define CFGR2_PREDIV1 ((uint32_t)0x0000000F) +#endif +#ifdef STM32F10X_CL + #define CFGR2_PREDIV2 ((uint32_t)0x000000F0) + #define CFGR2_PLL2MUL ((uint32_t)0x00000F00) + #define CFGR2_PLL3MUL ((uint32_t)0x0000F000) +#endif /* STM32F10X_CL */ + +/* RCC Flag Mask */ +#define FLAG_Mask ((uint8_t)0x1F) + +/* CIR register byte 2 (Bits[15:8]) base address */ +#define CIR_BYTE2_ADDRESS ((uint32_t)0x40021009) + +/* CIR register byte 3 (Bits[23:16]) base address */ +#define CIR_BYTE3_ADDRESS ((uint32_t)0x4002100A) + +/* CFGR register byte 4 (Bits[31:24]) base address */ +#define CFGR_BYTE4_ADDRESS ((uint32_t)0x40021007) + +/* BDCR register base address */ +#define BDCR_ADDRESS (PERIPH_BASE + BDCR_OFFSET) + +/** + * @} + */ + +/** @defgroup RCC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Variables + * @{ + */ + +static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; +static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8}; + +/** + * @} + */ + +/** @defgroup RCC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RCC_Private_Functions + * @{ + */ + +/** + * @brief Resets the RCC clock configuration to the default reset state. + * @param None + * @retval None + */ +void RCC_DeInit(void) +{ + /* Set HSION bit */ + RCC->CR |= (uint32_t)0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ +#ifndef STM32F10X_CL + RCC->CFGR &= (uint32_t)0xF8FF0000; +#else + RCC->CFGR &= (uint32_t)0xF0FF0000; +#endif /* STM32F10X_CL */ + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t)0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t)0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t)0xFF80FFFF; + +#ifdef STM32F10X_CL + /* Reset PLL2ON and PLL3ON bits */ + RCC->CR &= (uint32_t)0xEBFFFFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x00FF0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + /* Reset CFGR2 register */ + RCC->CFGR2 = 0x00000000; +#else + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; +#endif /* STM32F10X_CL */ + +} + +/** + * @brief Configures the External High Speed oscillator (HSE). + * @note HSE can not be stopped if it is used directly or through the PLL as system clock. + * @param RCC_HSE: specifies the new state of the HSE. + * This parameter can be one of the following values: + * @arg RCC_HSE_OFF: HSE oscillator OFF + * @arg RCC_HSE_ON: HSE oscillator ON + * @arg RCC_HSE_Bypass: HSE oscillator bypassed with external clock + * @retval None + */ +void RCC_HSEConfig(uint32_t RCC_HSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_HSE(RCC_HSE)); + /* Reset HSEON and HSEBYP bits before configuring the HSE ------------------*/ + /* Reset HSEON bit */ + RCC->CR &= CR_HSEON_Reset; + /* Reset HSEBYP bit */ + RCC->CR &= CR_HSEBYP_Reset; + /* Configure HSE (RCC_HSE_OFF is already covered by the code section above) */ + switch(RCC_HSE) + { + case RCC_HSE_ON: + /* Set HSEON bit */ + RCC->CR |= CR_HSEON_Set; + break; + + case RCC_HSE_Bypass: + /* Set HSEBYP and HSEON bits */ + RCC->CR |= CR_HSEBYP_Set | CR_HSEON_Set; + break; + + default: + break; + } +} + +/** + * @brief Waits for HSE start-up. + * @param None + * @retval An ErrorStatus enumuration value: + * - SUCCESS: HSE oscillator is stable and ready to use + * - ERROR: HSE oscillator not yet ready + */ +ErrorStatus RCC_WaitForHSEStartUp(void) +{ + __IO uint32_t StartUpCounter = 0; + ErrorStatus status = ERROR; + FlagStatus HSEStatus = RESET; + + /* Wait till HSE is ready and if Time out is reached exit */ + do + { + HSEStatus = RCC_GetFlagStatus(RCC_FLAG_HSERDY); + StartUpCounter++; + } while((StartUpCounter != HSE_STARTUP_TIMEOUT) && (HSEStatus == RESET)); + + if (RCC_GetFlagStatus(RCC_FLAG_HSERDY) != RESET) + { + status = SUCCESS; + } + else + { + status = ERROR; + } + return (status); +} + +/** + * @brief Adjusts the Internal High Speed oscillator (HSI) calibration value. + * @param HSICalibrationValue: specifies the calibration trimming value. + * This parameter must be a number between 0 and 0x1F. + * @retval None + */ +void RCC_AdjustHSICalibrationValue(uint8_t HSICalibrationValue) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_CALIBRATION_VALUE(HSICalibrationValue)); + tmpreg = RCC->CR; + /* Clear HSITRIM[4:0] bits */ + tmpreg &= CR_HSITRIM_Mask; + /* Set the HSITRIM[4:0] bits according to HSICalibrationValue value */ + tmpreg |= (uint32_t)HSICalibrationValue << 3; + /* Store the new value */ + RCC->CR = tmpreg; +} + +/** + * @brief Enables or disables the Internal High Speed oscillator (HSI). + * @note HSI can not be stopped if it is used directly or through the PLL as system clock. + * @param NewState: new state of the HSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_HSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_HSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the PLL clock source and multiplication factor. + * @note This function must be used only when the PLL is disabled. + * @param RCC_PLLSource: specifies the PLL entry clock source. + * For @b STM32_Connectivity_line_devices or @b STM32_Value_line_devices, + * this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_PREDIV1: PREDIV1 clock selected as PLL clock entry + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_PLLSource_HSI_Div2: HSI oscillator clock divided by 2 selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div1: HSE oscillator clock selected as PLL clock entry + * @arg RCC_PLLSource_HSE_Div2: HSE oscillator clock divided by 2 selected as PLL clock entry + * @param RCC_PLLMul: specifies the PLL multiplication factor. + * For @b STM32_Connectivity_line_devices, this parameter can be RCC_PLLMul_x where x:{[4,9], 6_5} + * For @b other_STM32_devices, this parameter can be RCC_PLLMul_x where x:[2,16] + * @retval None + */ +void RCC_PLLConfig(uint32_t RCC_PLLSource, uint32_t RCC_PLLMul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL_SOURCE(RCC_PLLSource)); + assert_param(IS_RCC_PLL_MUL(RCC_PLLMul)); + + tmpreg = RCC->CFGR; + /* Clear PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */ + tmpreg &= CFGR_PLL_Mask; + /* Set the PLL configuration bits */ + tmpreg |= RCC_PLLSource | RCC_PLLMul; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the PLL. + * @note The PLL can not be disabled if it is used as system clock. + * @param NewState: new state of the PLL. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLLCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLLON_BB = (uint32_t)NewState; +} + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) || defined (STM32F10X_CL) +/** + * @brief Configures the PREDIV1 division factor. + * @note + * - This function must be used only when the PLL is disabled. + * - This function applies only to STM32 Connectivity line and Value line + * devices. + * @param RCC_PREDIV1_Source: specifies the PREDIV1 clock source. + * This parameter can be one of the following values: + * @arg RCC_PREDIV1_Source_HSE: HSE selected as PREDIV1 clock + * @arg RCC_PREDIV1_Source_PLL2: PLL2 selected as PREDIV1 clock + * @note + * For @b STM32_Value_line_devices this parameter is always RCC_PREDIV1_Source_HSE + * @param RCC_PREDIV1_Div: specifies the PREDIV1 clock division factor. + * This parameter can be RCC_PREDIV1_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV1Config(uint32_t RCC_PREDIV1_Source, uint32_t RCC_PREDIV1_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV1_SOURCE(RCC_PREDIV1_Source)); + assert_param(IS_RCC_PREDIV1(RCC_PREDIV1_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV1[3:0] and PREDIV1SRC bits */ + tmpreg &= ~(CFGR2_PREDIV1 | CFGR2_PREDIV1SRC); + /* Set the PREDIV1 clock source and division factor */ + tmpreg |= RCC_PREDIV1_Source | RCC_PREDIV1_Div ; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} +#endif + +#ifdef STM32F10X_CL +/** + * @brief Configures the PREDIV2 division factor. + * @note + * - This function must be used only when both PLL2 and PLL3 are disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PREDIV2_Div: specifies the PREDIV2 clock division factor. + * This parameter can be RCC_PREDIV2_Divx where x:[1,16] + * @retval None + */ +void RCC_PREDIV2Config(uint32_t RCC_PREDIV2_Div) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PREDIV2(RCC_PREDIV2_Div)); + + tmpreg = RCC->CFGR2; + /* Clear PREDIV2[3:0] bits */ + tmpreg &= ~CFGR2_PREDIV2; + /* Set the PREDIV2 division factor */ + tmpreg |= RCC_PREDIV2_Div; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + +/** + * @brief Configures the PLL2 multiplication factor. + * @note + * - This function must be used only when the PLL2 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL2Mul: specifies the PLL2 multiplication factor. + * This parameter can be RCC_PLL2Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL2Config(uint32_t RCC_PLL2Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL2_MUL(RCC_PLL2Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL2Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL2MUL; + /* Set the PLL2 configuration bits */ + tmpreg |= RCC_PLL2Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL2. + * @note + * - The PLL2 can not be disabled if it is used indirectly as system clock + * (i.e. it is used as PLL clock entry that is used as System clock). + * - This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL2. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL2Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CR_PLL2ON_BB = (uint32_t)NewState; +} + + +/** + * @brief Configures the PLL3 multiplication factor. + * @note + * - This function must be used only when the PLL3 is disabled. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_PLL3Mul: specifies the PLL3 multiplication factor. + * This parameter can be RCC_PLL3Mul_x where x:{[8,14], 16, 20} + * @retval None + */ +void RCC_PLL3Config(uint32_t RCC_PLL3Mul) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_RCC_PLL3_MUL(RCC_PLL3Mul)); + + tmpreg = RCC->CFGR2; + /* Clear PLL3Mul[3:0] bits */ + tmpreg &= ~CFGR2_PLL3MUL; + /* Set the PLL3 configuration bits */ + tmpreg |= RCC_PLL3Mul; + /* Store the new value */ + RCC->CFGR2 = tmpreg; +} + + +/** + * @brief Enables or disables the PLL3. + * @note This function applies only to STM32 Connectivity line devices. + * @param NewState: new state of the PLL3. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_PLL3Cmd(FunctionalState NewState) +{ + /* Check the parameters */ + + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_PLL3ON_BB = (uint32_t)NewState; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the system clock (SYSCLK). + * @param RCC_SYSCLKSource: specifies the clock source used as system clock. + * This parameter can be one of the following values: + * @arg RCC_SYSCLKSource_HSI: HSI selected as system clock + * @arg RCC_SYSCLKSource_HSE: HSE selected as system clock + * @arg RCC_SYSCLKSource_PLLCLK: PLL selected as system clock + * @retval None + */ +void RCC_SYSCLKConfig(uint32_t RCC_SYSCLKSource) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_SYSCLK_SOURCE(RCC_SYSCLKSource)); + tmpreg = RCC->CFGR; + /* Clear SW[1:0] bits */ + tmpreg &= CFGR_SW_Mask; + /* Set SW[1:0] bits according to RCC_SYSCLKSource value */ + tmpreg |= RCC_SYSCLKSource; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Returns the clock source used as system clock. + * @param None + * @retval The clock source used as system clock. The returned value can + * be one of the following: + * - 0x00: HSI used as system clock + * - 0x04: HSE used as system clock + * - 0x08: PLL used as system clock + */ +uint8_t RCC_GetSYSCLKSource(void) +{ + return ((uint8_t)(RCC->CFGR & CFGR_SWS_Mask)); +} + +/** + * @brief Configures the AHB clock (HCLK). + * @param RCC_SYSCLK: defines the AHB clock divider. This clock is derived from + * the system clock (SYSCLK). + * This parameter can be one of the following values: + * @arg RCC_SYSCLK_Div1: AHB clock = SYSCLK + * @arg RCC_SYSCLK_Div2: AHB clock = SYSCLK/2 + * @arg RCC_SYSCLK_Div4: AHB clock = SYSCLK/4 + * @arg RCC_SYSCLK_Div8: AHB clock = SYSCLK/8 + * @arg RCC_SYSCLK_Div16: AHB clock = SYSCLK/16 + * @arg RCC_SYSCLK_Div64: AHB clock = SYSCLK/64 + * @arg RCC_SYSCLK_Div128: AHB clock = SYSCLK/128 + * @arg RCC_SYSCLK_Div256: AHB clock = SYSCLK/256 + * @arg RCC_SYSCLK_Div512: AHB clock = SYSCLK/512 + * @retval None + */ +void RCC_HCLKConfig(uint32_t RCC_SYSCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_HCLK(RCC_SYSCLK)); + tmpreg = RCC->CFGR; + /* Clear HPRE[3:0] bits */ + tmpreg &= CFGR_HPRE_Reset_Mask; + /* Set HPRE[3:0] bits according to RCC_SYSCLK value */ + tmpreg |= RCC_SYSCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the Low Speed APB clock (PCLK1). + * @param RCC_HCLK: defines the APB1 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB1 clock = HCLK + * @arg RCC_HCLK_Div2: APB1 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB1 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB1 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB1 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK1Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE1[2:0] bits */ + tmpreg &= CFGR_PPRE1_Reset_Mask; + /* Set PPRE1[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Configures the High Speed APB clock (PCLK2). + * @param RCC_HCLK: defines the APB2 clock divider. This clock is derived from + * the AHB clock (HCLK). + * This parameter can be one of the following values: + * @arg RCC_HCLK_Div1: APB2 clock = HCLK + * @arg RCC_HCLK_Div2: APB2 clock = HCLK/2 + * @arg RCC_HCLK_Div4: APB2 clock = HCLK/4 + * @arg RCC_HCLK_Div8: APB2 clock = HCLK/8 + * @arg RCC_HCLK_Div16: APB2 clock = HCLK/16 + * @retval None + */ +void RCC_PCLK2Config(uint32_t RCC_HCLK) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_PCLK(RCC_HCLK)); + tmpreg = RCC->CFGR; + /* Clear PPRE2[2:0] bits */ + tmpreg &= CFGR_PPRE2_Reset_Mask; + /* Set PPRE2[2:0] bits according to RCC_HCLK value */ + tmpreg |= RCC_HCLK << 3; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +/** + * @brief Enables or disables the specified RCC interrupts. + * @param RCC_IT: specifies the RCC interrupt sources to be enabled or disabled. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @param NewState: new state of the specified RCC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ITConfig(uint8_t RCC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_IT(RCC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Perform Byte access to RCC_CIR bits to enable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS |= RCC_IT; + } + else + { + /* Perform Byte access to RCC_CIR bits to disable the selected interrupts */ + *(__IO uint8_t *) CIR_BYTE2_ADDRESS &= (uint8_t)~RCC_IT; + } +} + +#ifndef STM32F10X_CL +/** + * @brief Configures the USB clock (USBCLK). + * @param RCC_USBCLKSource: specifies the USB clock source. This clock is + * derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_USBCLKSource_PLLCLK_1Div5: PLL clock divided by 1,5 selected as USB + * clock source + * @arg RCC_USBCLKSource_PLLCLK_Div1: PLL clock selected as USB clock source + * @retval None + */ +void RCC_USBCLKConfig(uint32_t RCC_USBCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_USBCLK_SOURCE(RCC_USBCLKSource)); + + *(__IO uint32_t *) CFGR_USBPRE_BB = RCC_USBCLKSource; +} +#else +/** + * @brief Configures the USB OTG FS clock (OTGFSCLK). + * This function applies only to STM32 Connectivity line devices. + * @param RCC_OTGFSCLKSource: specifies the USB OTG FS clock source. + * This clock is derived from the PLL output. + * This parameter can be one of the following values: + * @arg RCC_OTGFSCLKSource_PLLVCO_Div3: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @arg RCC_OTGFSCLKSource_PLLVCO_Div2: PLL VCO clock divided by 2 selected as USB OTG FS clock source + * @retval None + */ +void RCC_OTGFSCLKConfig(uint32_t RCC_OTGFSCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_OTGFSCLK_SOURCE(RCC_OTGFSCLKSource)); + + *(__IO uint32_t *) CFGR_OTGFSPRE_BB = RCC_OTGFSCLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the ADC clock (ADCCLK). + * @param RCC_PCLK2: defines the ADC clock divider. This clock is derived from + * the APB2 clock (PCLK2). + * This parameter can be one of the following values: + * @arg RCC_PCLK2_Div2: ADC clock = PCLK2/2 + * @arg RCC_PCLK2_Div4: ADC clock = PCLK2/4 + * @arg RCC_PCLK2_Div6: ADC clock = PCLK2/6 + * @arg RCC_PCLK2_Div8: ADC clock = PCLK2/8 + * @retval None + */ +void RCC_ADCCLKConfig(uint32_t RCC_PCLK2) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_RCC_ADCCLK(RCC_PCLK2)); + tmpreg = RCC->CFGR; + /* Clear ADCPRE[1:0] bits */ + tmpreg &= CFGR_ADCPRE_Reset_Mask; + /* Set ADCPRE[1:0] bits according to RCC_PCLK2 value */ + tmpreg |= RCC_PCLK2; + /* Store the new value */ + RCC->CFGR = tmpreg; +} + +#ifdef STM32F10X_CL +/** + * @brief Configures the I2S2 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S2 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S2CLKSource: specifies the I2S2 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S2CLKSource_SYSCLK: system clock selected as I2S2 clock entry + * @arg RCC_I2S2CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S2 clock entry + * @retval None + */ +void RCC_I2S2CLKConfig(uint32_t RCC_I2S2CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S2CLK_SOURCE(RCC_I2S2CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S2SRC_BB = RCC_I2S2CLKSource; +} + +/** + * @brief Configures the I2S3 clock source(I2S2CLK). + * @note + * - This function must be called before enabling I2S3 APB clock. + * - This function applies only to STM32 Connectivity line devices. + * @param RCC_I2S3CLKSource: specifies the I2S3 clock source. + * This parameter can be one of the following values: + * @arg RCC_I2S3CLKSource_SYSCLK: system clock selected as I2S3 clock entry + * @arg RCC_I2S3CLKSource_PLL3_VCO: PLL3 VCO clock selected as I2S3 clock entry + * @retval None + */ +void RCC_I2S3CLKConfig(uint32_t RCC_I2S3CLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_I2S3CLK_SOURCE(RCC_I2S3CLKSource)); + + *(__IO uint32_t *) CFGR2_I2S3SRC_BB = RCC_I2S3CLKSource; +} +#endif /* STM32F10X_CL */ + +/** + * @brief Configures the External Low Speed oscillator (LSE). + * @param RCC_LSE: specifies the new state of the LSE. + * This parameter can be one of the following values: + * @arg RCC_LSE_OFF: LSE oscillator OFF + * @arg RCC_LSE_ON: LSE oscillator ON + * @arg RCC_LSE_Bypass: LSE oscillator bypassed with external clock + * @retval None + */ +void RCC_LSEConfig(uint8_t RCC_LSE) +{ + /* Check the parameters */ + assert_param(IS_RCC_LSE(RCC_LSE)); + /* Reset LSEON and LSEBYP bits before configuring the LSE ------------------*/ + /* Reset LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Reset LSEBYP bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_OFF; + /* Configure LSE (RCC_LSE_OFF is already covered by the code section above) */ + switch(RCC_LSE) + { + case RCC_LSE_ON: + /* Set LSEON bit */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_ON; + break; + + case RCC_LSE_Bypass: + /* Set LSEBYP and LSEON bits */ + *(__IO uint8_t *) BDCR_ADDRESS = RCC_LSE_Bypass | RCC_LSE_ON; + break; + + default: + break; + } +} + +/** + * @brief Enables or disables the Internal Low Speed oscillator (LSI). + * @note LSI can not be disabled if the IWDG is running. + * @param NewState: new state of the LSI. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_LSICmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CSR_LSION_BB = (uint32_t)NewState; +} + +/** + * @brief Configures the RTC clock (RTCCLK). + * @note Once the RTC clock is selected it can't be changed unless the Backup domain is reset. + * @param RCC_RTCCLKSource: specifies the RTC clock source. + * This parameter can be one of the following values: + * @arg RCC_RTCCLKSource_LSE: LSE selected as RTC clock + * @arg RCC_RTCCLKSource_LSI: LSI selected as RTC clock + * @arg RCC_RTCCLKSource_HSE_Div128: HSE clock divided by 128 selected as RTC clock + * @retval None + */ +void RCC_RTCCLKConfig(uint32_t RCC_RTCCLKSource) +{ + /* Check the parameters */ + assert_param(IS_RCC_RTCCLK_SOURCE(RCC_RTCCLKSource)); + /* Select the RTC clock source */ + RCC->BDCR |= RCC_RTCCLKSource; +} + +/** + * @brief Enables or disables the RTC clock. + * @note This function must be used only after the RTC clock was selected using the RCC_RTCCLKConfig function. + * @param NewState: new state of the RTC clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_RTCCLKCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_RTCEN_BB = (uint32_t)NewState; +} + +/** + * @brief Returns the frequencies of different on chip clocks. + * @param RCC_Clocks: pointer to a RCC_ClocksTypeDef structure which will hold + * the clocks frequencies. + * @note The result of this function could be not correct when using + * fractional value for HSE crystal. + * @retval None + */ +void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0, presc = 0; + +#ifdef STM32F10X_CL + uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0; +#endif /* STM32F10X_CL */ + +#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + uint32_t prediv1factor = 0; +#endif + + /* Get SYSCLK source -------------------------------------------------------*/ + tmp = RCC->CFGR & CFGR_SWS_Mask; + + switch (tmp) + { + case 0x00: /* HSI used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ----------------------*/ + pllmull = RCC->CFGR & CFGR_PLLMull_Mask; + pllsource = RCC->CFGR & CFGR_PLLSRC_Mask; + +#ifndef STM32F10X_CL + pllmull = ( pllmull >> 18) + 2; + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + } + else + { + #if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || defined (STM32F10X_HD_VL) + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + #else + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET) + {/* HSE oscillator clock divided by 2 */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE >> 1) * pllmull; + } + else + { + RCC_Clocks->SYSCLK_Frequency = HSE_VALUE * pllmull; + } + #endif + } +#else + pllmull = pllmull >> 18; + + if (pllmull != 0x0D) + { + pllmull += 2; + } + else + { /* PLL multiplication factor = PLL input clock * 6.5 */ + pllmull = 13 / 2; + } + + if (pllsource == 0x00) + {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + } + else + {/* PREDIV1 selected as PLL clock entry */ + + /* Get PREDIV1 clock source and division factor */ + prediv1source = RCC->CFGR2 & CFGR2_PREDIV1SRC; + prediv1factor = (RCC->CFGR2 & CFGR2_PREDIV1) + 1; + + if (prediv1source == 0) + { /* HSE oscillator clock selected as PREDIV1 clock entry */ + RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + } + else + {/* PLL2 clock selected as PREDIV1 clock entry */ + + /* Get PREDIV2 division factor and PLL2 multiplication factor */ + prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1; + pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; + RCC_Clocks->SYSCLK_Frequency = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull; + } + } +#endif /* STM32F10X_CL */ + break; + + default: + RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; + break; + } + + /* Compute HCLK, PCLK1, PCLK2 and ADCCLK clocks frequencies ----------------*/ + /* Get HCLK prescaler */ + tmp = RCC->CFGR & CFGR_HPRE_Set_Mask; + tmp = tmp >> 4; + presc = APBAHBPrescTable[tmp]; + /* HCLK clock frequency */ + RCC_Clocks->HCLK_Frequency = RCC_Clocks->SYSCLK_Frequency >> presc; + /* Get PCLK1 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE1_Set_Mask; + tmp = tmp >> 8; + presc = APBAHBPrescTable[tmp]; + /* PCLK1 clock frequency */ + RCC_Clocks->PCLK1_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get PCLK2 prescaler */ + tmp = RCC->CFGR & CFGR_PPRE2_Set_Mask; + tmp = tmp >> 11; + presc = APBAHBPrescTable[tmp]; + /* PCLK2 clock frequency */ + RCC_Clocks->PCLK2_Frequency = RCC_Clocks->HCLK_Frequency >> presc; + /* Get ADCCLK prescaler */ + tmp = RCC->CFGR & CFGR_ADCPRE_Set_Mask; + tmp = tmp >> 14; + presc = ADCPrescTable[tmp]; + /* ADCCLK clock frequency */ + RCC_Clocks->ADCCLK_Frequency = RCC_Clocks->PCLK2_Frequency / presc; +} + +/** + * @brief Enables or disables the AHB peripheral clock. + * @param RCC_AHBPeriph: specifies the AHB peripheral to gates its clock. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @arg RCC_AHBPeriph_ETH_MAC_Tx + * @arg RCC_AHBPeriph_ETH_MAC_Rx + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_AHBPeriph_DMA1 + * @arg RCC_AHBPeriph_DMA2 + * @arg RCC_AHBPeriph_SRAM + * @arg RCC_AHBPeriph_FLITF + * @arg RCC_AHBPeriph_CRC + * @arg RCC_AHBPeriph_FSMC + * @arg RCC_AHBPeriph_SDIO + * + * @note SRAM and FLITF clock can be disabled only during sleep mode. + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBENR |= RCC_AHBPeriph; + } + else + { + RCC->AHBENR &= ~RCC_AHBPeriph; + } +} + +/** + * @brief Enables or disables the High Speed APB (APB2) peripheral clock. + * @param RCC_APB2Periph: specifies the APB2 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphClockCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2ENR |= RCC_APB2Periph; + } + else + { + RCC->APB2ENR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Enables or disables the Low Speed APB (APB1) peripheral clock. + * @param RCC_APB1Periph: specifies the APB1 peripheral to gates its clock. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1ENR |= RCC_APB1Periph; + } + else + { + RCC->APB1ENR &= ~RCC_APB1Periph; + } +} + +#ifdef STM32F10X_CL +/** + * @brief Forces or releases AHB peripheral reset. + * @note This function applies only to STM32 Connectivity line devices. + * @param RCC_AHBPeriph: specifies the AHB peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_AHBPeriph_OTG_FS + * @arg RCC_AHBPeriph_ETH_MAC + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_AHBPeriphResetCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH_RESET(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RCC->AHBRSTR |= RCC_AHBPeriph; + } + else + { + RCC->AHBRSTR &= ~RCC_AHBPeriph; + } +} +#endif /* STM32F10X_CL */ + +/** + * @brief Forces or releases High Speed APB (APB2) peripheral reset. + * @param RCC_APB2Periph: specifies the APB2 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB2Periph_AFIO, RCC_APB2Periph_GPIOA, RCC_APB2Periph_GPIOB, + * RCC_APB2Periph_GPIOC, RCC_APB2Periph_GPIOD, RCC_APB2Periph_GPIOE, + * RCC_APB2Periph_GPIOF, RCC_APB2Periph_GPIOG, RCC_APB2Periph_ADC1, + * RCC_APB2Periph_ADC2, RCC_APB2Periph_TIM1, RCC_APB2Periph_SPI1, + * RCC_APB2Periph_TIM8, RCC_APB2Periph_USART1, RCC_APB2Periph_ADC3, + * RCC_APB2Periph_TIM15, RCC_APB2Periph_TIM16, RCC_APB2Periph_TIM17, + * RCC_APB2Periph_TIM9, RCC_APB2Periph_TIM10, RCC_APB2Periph_TIM11 + * @param NewState: new state of the specified peripheral reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB2PeriphResetCmd(uint32_t RCC_APB2Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB2_PERIPH(RCC_APB2Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB2RSTR |= RCC_APB2Periph; + } + else + { + RCC->APB2RSTR &= ~RCC_APB2Periph; + } +} + +/** + * @brief Forces or releases Low Speed APB (APB1) peripheral reset. + * @param RCC_APB1Periph: specifies the APB1 peripheral to reset. + * This parameter can be any combination of the following values: + * @arg RCC_APB1Periph_TIM2, RCC_APB1Periph_TIM3, RCC_APB1Periph_TIM4, + * RCC_APB1Periph_TIM5, RCC_APB1Periph_TIM6, RCC_APB1Periph_TIM7, + * RCC_APB1Periph_WWDG, RCC_APB1Periph_SPI2, RCC_APB1Periph_SPI3, + * RCC_APB1Periph_USART2, RCC_APB1Periph_USART3, RCC_APB1Periph_USART4, + * RCC_APB1Periph_USART5, RCC_APB1Periph_I2C1, RCC_APB1Periph_I2C2, + * RCC_APB1Periph_USB, RCC_APB1Periph_CAN1, RCC_APB1Periph_BKP, + * RCC_APB1Periph_PWR, RCC_APB1Periph_DAC, RCC_APB1Periph_CEC, + * RCC_APB1Periph_TIM12, RCC_APB1Periph_TIM13, RCC_APB1Periph_TIM14 + * @param NewState: new state of the specified peripheral clock. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_APB1PeriphResetCmd(uint32_t RCC_APB1Periph, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RCC_APB1_PERIPH(RCC_APB1Periph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + RCC->APB1RSTR |= RCC_APB1Periph; + } + else + { + RCC->APB1RSTR &= ~RCC_APB1Periph; + } +} + +/** + * @brief Forces or releases the Backup domain reset. + * @param NewState: new state of the Backup domain reset. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_BackupResetCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) BDCR_BDRST_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the Clock Security System. + * @param NewState: new state of the Clock Security System.. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RCC_ClockSecuritySystemCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + *(__IO uint32_t *) CR_CSSON_BB = (uint32_t)NewState; +} + +/** + * @brief Selects the clock source to output on MCO pin. + * @param RCC_MCO: specifies the clock source to output. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * @arg RCC_MCO_PLL2CLK: PLL2 clock selected + * @arg RCC_MCO_PLL3CLK_Div2: PLL3 clock divided by 2 selected + * @arg RCC_MCO_XT1: External 3-25 MHz oscillator clock selected + * @arg RCC_MCO_PLL3CLK: PLL3 clock selected + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_MCO_NoClock: No clock selected + * @arg RCC_MCO_SYSCLK: System clock selected + * @arg RCC_MCO_HSI: HSI oscillator clock selected + * @arg RCC_MCO_HSE: HSE oscillator clock selected + * @arg RCC_MCO_PLLCLK_Div2: PLL clock divided by 2 selected + * + * @retval None + */ +void RCC_MCOConfig(uint8_t RCC_MCO) +{ + /* Check the parameters */ + assert_param(IS_RCC_MCO(RCC_MCO)); + + /* Perform Byte access to MCO bits to select the MCO source */ + *(__IO uint8_t *) CFGR_BYTE4_ADDRESS = RCC_MCO; +} + +/** + * @brief Checks whether the specified RCC flag is set or not. + * @param RCC_FLAG: specifies the flag to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_PLL2RDY: PLL2 clock ready + * @arg RCC_FLAG_PLL3RDY: PLL3 clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready + * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready + * @arg RCC_FLAG_PLLRDY: PLL clock ready + * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready + * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready + * @arg RCC_FLAG_PINRST: Pin reset + * @arg RCC_FLAG_PORRST: POR/PDR reset + * @arg RCC_FLAG_SFTRST: Software reset + * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset + * @arg RCC_FLAG_WWDGRST: Window Watchdog reset + * @arg RCC_FLAG_LPWRRST: Low Power reset + * + * @retval The new state of RCC_FLAG (SET or RESET). + */ +FlagStatus RCC_GetFlagStatus(uint8_t RCC_FLAG) +{ + uint32_t tmp = 0; + uint32_t statusreg = 0; + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_FLAG(RCC_FLAG)); + + /* Get the RCC register index */ + tmp = RCC_FLAG >> 5; + if (tmp == 1) /* The flag to check is in CR register */ + { + statusreg = RCC->CR; + } + else if (tmp == 2) /* The flag to check is in BDCR register */ + { + statusreg = RCC->BDCR; + } + else /* The flag to check is in CSR register */ + { + statusreg = RCC->CSR; + } + + /* Get the flag position */ + tmp = RCC_FLAG & FLAG_Mask; + if ((statusreg & ((uint32_t)1 << tmp)) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the flag status */ + return bitstatus; +} + +/** + * @brief Clears the RCC reset flags. + * @note The reset flags are: RCC_FLAG_PINRST, RCC_FLAG_PORRST, RCC_FLAG_SFTRST, + * RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST, RCC_FLAG_LPWRRST + * @param None + * @retval None + */ +void RCC_ClearFlag(void) +{ + /* Set RMVF bit to clear the reset flags */ + RCC->CSR |= CSR_RMVF_Set; +} + +/** + * @brief Checks whether the specified RCC interrupt has occurred or not. + * @param RCC_IT: specifies the RCC interrupt source to check. + * + * For @b STM32_Connectivity_line_devices, this parameter can be one of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be one of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * @retval The new state of RCC_IT (SET or RESET). + */ +ITStatus RCC_GetITStatus(uint8_t RCC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RCC_GET_IT(RCC_IT)); + + /* Check the status of the specified RCC interrupt */ + if ((RCC->CIR & RCC_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + /* Return the RCC_IT status */ + return bitstatus; +} + +/** + * @brief Clears the RCC's interrupt pending bits. + * @param RCC_IT: specifies the interrupt pending bit to clear. + * + * For @b STM32_Connectivity_line_devices, this parameter can be any combination + * of the following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * @arg RCC_IT_PLL2RDY: PLL2 ready interrupt + * @arg RCC_IT_PLL3RDY: PLL3 ready interrupt + * @arg RCC_IT_CSS: Clock Security System interrupt + * + * For @b other_STM32_devices, this parameter can be any combination of the + * following values: + * @arg RCC_IT_LSIRDY: LSI ready interrupt + * @arg RCC_IT_LSERDY: LSE ready interrupt + * @arg RCC_IT_HSIRDY: HSI ready interrupt + * @arg RCC_IT_HSERDY: HSE ready interrupt + * @arg RCC_IT_PLLRDY: PLL ready interrupt + * + * @arg RCC_IT_CSS: Clock Security System interrupt + * @retval None + */ +void RCC_ClearITPendingBit(uint8_t RCC_IT) +{ + /* Check the parameters */ + assert_param(IS_RCC_CLEAR_IT(RCC_IT)); + + /* Perform Byte access to RCC_CIR[23:16] bits to clear the selected interrupt + pending bits */ + *(__IO uint8_t *) CIR_BYTE3_ADDRESS = RCC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c new file mode 100755 index 0000000000..f798d2bd6f --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_rtc.c @@ -0,0 +1,339 @@ +/** + ****************************************************************************** + * @file stm32f10x_rtc.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the RTC firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_rtc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup RTC + * @brief RTC driver modules + * @{ + */ + +/** @defgroup RTC_Private_TypesDefinitions + * @{ + */ +/** + * @} + */ + +/** @defgroup RTC_Private_Defines + * @{ + */ +#define RTC_LSB_MASK ((uint32_t)0x0000FFFF) /*!< RTC LSB Mask */ +#define PRLH_MSB_MASK ((uint32_t)0x000F0000) /*!< RTC Prescaler MSB Mask */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup RTC_Private_Functions + * @{ + */ + +/** + * @brief Enables or disables the specified RTC interrupts. + * @param RTC_IT: specifies the RTC interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @param NewState: new state of the specified RTC interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void RTC_ITConfig(uint16_t RTC_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + RTC->CRH |= RTC_IT; + } + else + { + RTC->CRH &= (uint16_t)~RTC_IT; + } +} + +/** + * @brief Enters the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_EnterConfigMode(void) +{ + /* Set the CNF flag to enter in the Configuration Mode */ + RTC->CRL |= RTC_CRL_CNF; +} + +/** + * @brief Exits from the RTC configuration mode. + * @param None + * @retval None + */ +void RTC_ExitConfigMode(void) +{ + /* Reset the CNF flag to exit from the Configuration Mode */ + RTC->CRL &= (uint16_t)~((uint16_t)RTC_CRL_CNF); +} + +/** + * @brief Gets the RTC counter value. + * @param None + * @retval RTC counter value. + */ +uint32_t RTC_GetCounter(void) +{ + uint16_t tmp = 0; + tmp = RTC->CNTL; + return (((uint32_t)RTC->CNTH << 16 ) | tmp) ; +} + +/** + * @brief Sets the RTC counter value. + * @param CounterValue: RTC counter new value. + * @retval None + */ +void RTC_SetCounter(uint32_t CounterValue) +{ + RTC_EnterConfigMode(); + /* Set RTC COUNTER MSB word */ + RTC->CNTH = CounterValue >> 16; + /* Set RTC COUNTER LSB word */ + RTC->CNTL = (CounterValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC prescaler value. + * @param PrescalerValue: RTC prescaler new value. + * @retval None + */ +void RTC_SetPrescaler(uint32_t PrescalerValue) +{ + /* Check the parameters */ + assert_param(IS_RTC_PRESCALER(PrescalerValue)); + + RTC_EnterConfigMode(); + /* Set RTC PRESCALER MSB word */ + RTC->PRLH = (PrescalerValue & PRLH_MSB_MASK) >> 16; + /* Set RTC PRESCALER LSB word */ + RTC->PRLL = (PrescalerValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Sets the RTC alarm value. + * @param AlarmValue: RTC alarm new value. + * @retval None + */ +void RTC_SetAlarm(uint32_t AlarmValue) +{ + RTC_EnterConfigMode(); + /* Set the ALARM MSB word */ + RTC->ALRH = AlarmValue >> 16; + /* Set the ALARM LSB word */ + RTC->ALRL = (AlarmValue & RTC_LSB_MASK); + RTC_ExitConfigMode(); +} + +/** + * @brief Gets the RTC divider value. + * @param None + * @retval RTC Divider value. + */ +uint32_t RTC_GetDivider(void) +{ + uint32_t tmp = 0x00; + tmp = ((uint32_t)RTC->DIVH & (uint32_t)0x000F) << 16; + tmp |= RTC->DIVL; + return tmp; +} + +/** + * @brief Waits until last write operation on RTC registers has finished. + * @note This function must be called before any write to RTC registers. + * @param None + * @retval None + */ +void RTC_WaitForLastTask(void) +{ + /* Loop until RTOFF flag is set */ + while ((RTC->CRL & RTC_FLAG_RTOFF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Waits until the RTC registers (RTC_CNT, RTC_ALR and RTC_PRL) + * are synchronized with RTC APB clock. + * @note This function must be called before any read operation after an APB reset + * or an APB clock stop. + * @param None + * @retval None + */ +void RTC_WaitForSynchro(void) +{ + /* Clear RSF flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG_RSF; + /* Loop until RSF flag is set */ + while ((RTC->CRL & RTC_FLAG_RSF) == (uint16_t)RESET) + { + } +} + +/** + * @brief Checks whether the specified RTC flag is set or not. + * @param RTC_FLAG: specifies the flag to check. + * This parameter can be one the following values: + * @arg RTC_FLAG_RTOFF: RTC Operation OFF flag + * @arg RTC_FLAG_RSF: Registers Synchronized flag + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval The new state of RTC_FLAG (SET or RESET). + */ +FlagStatus RTC_GetFlagStatus(uint16_t RTC_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_RTC_GET_FLAG(RTC_FLAG)); + + if ((RTC->CRL & RTC_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's pending flags. + * @param RTC_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg RTC_FLAG_RSF: Registers Synchronized flag. This flag is cleared only after + * an APB reset or an APB Clock stop. + * @arg RTC_FLAG_OW: Overflow flag + * @arg RTC_FLAG_ALR: Alarm flag + * @arg RTC_FLAG_SEC: Second flag + * @retval None + */ +void RTC_ClearFlag(uint16_t RTC_FLAG) +{ + /* Check the parameters */ + assert_param(IS_RTC_CLEAR_FLAG(RTC_FLAG)); + + /* Clear the corresponding RTC flag */ + RTC->CRL &= (uint16_t)~RTC_FLAG; +} + +/** + * @brief Checks whether the specified RTC interrupt has occurred or not. + * @param RTC_IT: specifies the RTC interrupts sources to check. + * This parameter can be one of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval The new state of the RTC_IT (SET or RESET). + */ +ITStatus RTC_GetITStatus(uint16_t RTC_IT) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_RTC_GET_IT(RTC_IT)); + + bitstatus = (ITStatus)(RTC->CRL & RTC_IT); + if (((RTC->CRH & RTC_IT) != (uint16_t)RESET) && (bitstatus != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the RTC's interrupt pending bits. + * @param RTC_IT: specifies the interrupt pending bit to clear. + * This parameter can be any combination of the following values: + * @arg RTC_IT_OW: Overflow interrupt + * @arg RTC_IT_ALR: Alarm interrupt + * @arg RTC_IT_SEC: Second interrupt + * @retval None + */ +void RTC_ClearITPendingBit(uint16_t RTC_IT) +{ + /* Check the parameters */ + assert_param(IS_RTC_IT(RTC_IT)); + + /* Clear the corresponding RTC pending bit */ + RTC->CRL &= (uint16_t)~RTC_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c new file mode 100755 index 0000000000..d1870cef15 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_sdio.c @@ -0,0 +1,799 @@ +/** + ****************************************************************************** + * @file stm32f10x_sdio.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the SDIO firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_sdio.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SDIO + * @brief SDIO driver modules + * @{ + */ + +/** @defgroup SDIO_Private_TypesDefinitions + * @{ + */ + +/* ------------ SDIO registers bit address in the alias region ----------- */ +#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) + +/* --- CLKCR Register ---*/ + +/* Alias word address of CLKEN bit */ +#define CLKCR_OFFSET (SDIO_OFFSET + 0x04) +#define CLKEN_BitNumber 0x08 +#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32) + (CLKEN_BitNumber * 4)) + +/* --- CMD Register ---*/ + +/* Alias word address of SDIOSUSPEND bit */ +#define CMD_OFFSET (SDIO_OFFSET + 0x0C) +#define SDIOSUSPEND_BitNumber 0x0B +#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (SDIOSUSPEND_BitNumber * 4)) + +/* Alias word address of ENCMDCOMPL bit */ +#define ENCMDCOMPL_BitNumber 0x0C +#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ENCMDCOMPL_BitNumber * 4)) + +/* Alias word address of NIEN bit */ +#define NIEN_BitNumber 0x0D +#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (NIEN_BitNumber * 4)) + +/* Alias word address of ATACMD bit */ +#define ATACMD_BitNumber 0x0E +#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32) + (ATACMD_BitNumber * 4)) + +/* --- DCTRL Register ---*/ + +/* Alias word address of DMAEN bit */ +#define DCTRL_OFFSET (SDIO_OFFSET + 0x2C) +#define DMAEN_BitNumber 0x03 +#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (DMAEN_BitNumber * 4)) + +/* Alias word address of RWSTART bit */ +#define RWSTART_BitNumber 0x08 +#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTART_BitNumber * 4)) + +/* Alias word address of RWSTOP bit */ +#define RWSTOP_BitNumber 0x09 +#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWSTOP_BitNumber * 4)) + +/* Alias word address of RWMOD bit */ +#define RWMOD_BitNumber 0x0A +#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (RWMOD_BitNumber * 4)) + +/* Alias word address of SDIOEN bit */ +#define SDIOEN_BitNumber 0x0B +#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32) + (SDIOEN_BitNumber * 4)) + +/* ---------------------- SDIO registers bit mask ------------------------ */ + +/* --- CLKCR Register ---*/ + +/* CLKCR register clear mask */ +#define CLKCR_CLEAR_MASK ((uint32_t)0xFFFF8100) + +/* --- PWRCTRL Register ---*/ + +/* SDIO PWRCTRL Mask */ +#define PWR_PWRCTRL_MASK ((uint32_t)0xFFFFFFFC) + +/* --- DCTRL Register ---*/ + +/* SDIO DCTRL Clear Mask */ +#define DCTRL_CLEAR_MASK ((uint32_t)0xFFFFFF08) + +/* --- CMD Register ---*/ + +/* CMD Register clear mask */ +#define CMD_CLEAR_MASK ((uint32_t)0xFFFFF800) + +/* SDIO RESP Registers Address */ +#define SDIO_RESP_ADDR ((uint32_t)(SDIO_BASE + 0x14)) + +/** + * @} + */ + +/** @defgroup SDIO_Private_Defines + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SDIO_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SDIO peripheral registers to their default reset values. + * @param None + * @retval None + */ +void SDIO_DeInit(void) +{ + SDIO->POWER = 0x00000000; + SDIO->CLKCR = 0x00000000; + SDIO->ARG = 0x00000000; + SDIO->CMD = 0x00000000; + SDIO->DTIMER = 0x00000000; + SDIO->DLEN = 0x00000000; + SDIO->DCTRL = 0x00000000; + SDIO->ICR = 0x00C007FF; + SDIO->MASK = 0x00000000; +} + +/** + * @brief Initializes the SDIO peripheral according to the specified + * parameters in the SDIO_InitStruct. + * @param SDIO_InitStruct : pointer to a SDIO_InitTypeDef structure + * that contains the configuration information for the SDIO peripheral. + * @retval None + */ +void SDIO_Init(SDIO_InitTypeDef* SDIO_InitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CLOCK_EDGE(SDIO_InitStruct->SDIO_ClockEdge)); + assert_param(IS_SDIO_CLOCK_BYPASS(SDIO_InitStruct->SDIO_ClockBypass)); + assert_param(IS_SDIO_CLOCK_POWER_SAVE(SDIO_InitStruct->SDIO_ClockPowerSave)); + assert_param(IS_SDIO_BUS_WIDE(SDIO_InitStruct->SDIO_BusWide)); + assert_param(IS_SDIO_HARDWARE_FLOW_CONTROL(SDIO_InitStruct->SDIO_HardwareFlowControl)); + +/*---------------------------- SDIO CLKCR Configuration ------------------------*/ + /* Get the SDIO CLKCR value */ + tmpreg = SDIO->CLKCR; + + /* Clear CLKDIV, PWRSAV, BYPASS, WIDBUS, NEGEDGE, HWFC_EN bits */ + tmpreg &= CLKCR_CLEAR_MASK; + + /* Set CLKDIV bits according to SDIO_ClockDiv value */ + /* Set PWRSAV bit according to SDIO_ClockPowerSave value */ + /* Set BYPASS bit according to SDIO_ClockBypass value */ + /* Set WIDBUS bits according to SDIO_BusWide value */ + /* Set NEGEDGE bits according to SDIO_ClockEdge value */ + /* Set HWFC_EN bits according to SDIO_HardwareFlowControl value */ + tmpreg |= (SDIO_InitStruct->SDIO_ClockDiv | SDIO_InitStruct->SDIO_ClockPowerSave | + SDIO_InitStruct->SDIO_ClockBypass | SDIO_InitStruct->SDIO_BusWide | + SDIO_InitStruct->SDIO_ClockEdge | SDIO_InitStruct->SDIO_HardwareFlowControl); + + /* Write to SDIO CLKCR */ + SDIO->CLKCR = tmpreg; +} + +/** + * @brief Fills each SDIO_InitStruct member with its default value. + * @param SDIO_InitStruct: pointer to an SDIO_InitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_StructInit(SDIO_InitTypeDef* SDIO_InitStruct) +{ + /* SDIO_InitStruct members default value */ + SDIO_InitStruct->SDIO_ClockDiv = 0x00; + SDIO_InitStruct->SDIO_ClockEdge = SDIO_ClockEdge_Rising; + SDIO_InitStruct->SDIO_ClockBypass = SDIO_ClockBypass_Disable; + SDIO_InitStruct->SDIO_ClockPowerSave = SDIO_ClockPowerSave_Disable; + SDIO_InitStruct->SDIO_BusWide = SDIO_BusWide_1b; + SDIO_InitStruct->SDIO_HardwareFlowControl = SDIO_HardwareFlowControl_Disable; +} + +/** + * @brief Enables or disables the SDIO Clock. + * @param NewState: new state of the SDIO Clock. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ClockCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CLKCR_CLKEN_BB = (uint32_t)NewState; +} + +/** + * @brief Sets the power status of the controller. + * @param SDIO_PowerState: new state of the Power state. + * This parameter can be one of the following values: + * @arg SDIO_PowerState_OFF + * @arg SDIO_PowerState_ON + * @retval None + */ +void SDIO_SetPowerState(uint32_t SDIO_PowerState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_POWER_STATE(SDIO_PowerState)); + + SDIO->POWER &= PWR_PWRCTRL_MASK; + SDIO->POWER |= SDIO_PowerState; +} + +/** + * @brief Gets the power status of the controller. + * @param None + * @retval Power status of the controller. The returned value can + * be one of the following: + * - 0x00: Power OFF + * - 0x02: Power UP + * - 0x03: Power ON + */ +uint32_t SDIO_GetPowerState(void) +{ + return (SDIO->POWER & (~PWR_PWRCTRL_MASK)); +} + +/** + * @brief Enables or disables the SDIO interrupts. + * @param SDIO_IT: specifies the SDIO interrupt sources to be enabled or disabled. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @param NewState: new state of the specified SDIO interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_ITConfig(uint32_t SDIO_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SDIO_IT(SDIO_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the SDIO interrupts */ + SDIO->MASK |= SDIO_IT; + } + else + { + /* Disable the SDIO interrupts */ + SDIO->MASK &= ~SDIO_IT; + } +} + +/** + * @brief Enables or disables the SDIO DMA request. + * @param NewState: new state of the selected SDIO DMA request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_DMACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_DMAEN_BB = (uint32_t)NewState; +} + +/** + * @brief Initializes the SDIO Command according to the specified + * parameters in the SDIO_CmdInitStruct and send the command. + * @param SDIO_CmdInitStruct : pointer to a SDIO_CmdInitTypeDef + * structure that contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_SendCommand(SDIO_CmdInitTypeDef *SDIO_CmdInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_CMD_INDEX(SDIO_CmdInitStruct->SDIO_CmdIndex)); + assert_param(IS_SDIO_RESPONSE(SDIO_CmdInitStruct->SDIO_Response)); + assert_param(IS_SDIO_WAIT(SDIO_CmdInitStruct->SDIO_Wait)); + assert_param(IS_SDIO_CPSM(SDIO_CmdInitStruct->SDIO_CPSM)); + +/*---------------------------- SDIO ARG Configuration ------------------------*/ + /* Set the SDIO Argument value */ + SDIO->ARG = SDIO_CmdInitStruct->SDIO_Argument; + +/*---------------------------- SDIO CMD Configuration ------------------------*/ + /* Get the SDIO CMD value */ + tmpreg = SDIO->CMD; + /* Clear CMDINDEX, WAITRESP, WAITINT, WAITPEND, CPSMEN bits */ + tmpreg &= CMD_CLEAR_MASK; + /* Set CMDINDEX bits according to SDIO_CmdIndex value */ + /* Set WAITRESP bits according to SDIO_Response value */ + /* Set WAITINT and WAITPEND bits according to SDIO_Wait value */ + /* Set CPSMEN bits according to SDIO_CPSM value */ + tmpreg |= (uint32_t)SDIO_CmdInitStruct->SDIO_CmdIndex | SDIO_CmdInitStruct->SDIO_Response + | SDIO_CmdInitStruct->SDIO_Wait | SDIO_CmdInitStruct->SDIO_CPSM; + + /* Write to SDIO CMD */ + SDIO->CMD = tmpreg; +} + +/** + * @brief Fills each SDIO_CmdInitStruct member with its default value. + * @param SDIO_CmdInitStruct: pointer to an SDIO_CmdInitTypeDef + * structure which will be initialized. + * @retval None + */ +void SDIO_CmdStructInit(SDIO_CmdInitTypeDef* SDIO_CmdInitStruct) +{ + /* SDIO_CmdInitStruct members default value */ + SDIO_CmdInitStruct->SDIO_Argument = 0x00; + SDIO_CmdInitStruct->SDIO_CmdIndex = 0x00; + SDIO_CmdInitStruct->SDIO_Response = SDIO_Response_No; + SDIO_CmdInitStruct->SDIO_Wait = SDIO_Wait_No; + SDIO_CmdInitStruct->SDIO_CPSM = SDIO_CPSM_Disable; +} + +/** + * @brief Returns command index of last command for which response received. + * @param None + * @retval Returns the command index of the last command response received. + */ +uint8_t SDIO_GetCommandResponse(void) +{ + return (uint8_t)(SDIO->RESPCMD); +} + +/** + * @brief Returns response received from the card for the last command. + * @param SDIO_RESP: Specifies the SDIO response register. + * This parameter can be one of the following values: + * @arg SDIO_RESP1: Response Register 1 + * @arg SDIO_RESP2: Response Register 2 + * @arg SDIO_RESP3: Response Register 3 + * @arg SDIO_RESP4: Response Register 4 + * @retval The Corresponding response register value. + */ +uint32_t SDIO_GetResponse(uint32_t SDIO_RESP) +{ + __IO uint32_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_RESP(SDIO_RESP)); + + tmp = SDIO_RESP_ADDR + SDIO_RESP; + + return (*(__IO uint32_t *) tmp); +} + +/** + * @brief Initializes the SDIO data path according to the specified + * parameters in the SDIO_DataInitStruct. + * @param SDIO_DataInitStruct : pointer to a SDIO_DataInitTypeDef structure that + * contains the configuration information for the SDIO command. + * @retval None + */ +void SDIO_DataConfig(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_SDIO_DATA_LENGTH(SDIO_DataInitStruct->SDIO_DataLength)); + assert_param(IS_SDIO_BLOCK_SIZE(SDIO_DataInitStruct->SDIO_DataBlockSize)); + assert_param(IS_SDIO_TRANSFER_DIR(SDIO_DataInitStruct->SDIO_TransferDir)); + assert_param(IS_SDIO_TRANSFER_MODE(SDIO_DataInitStruct->SDIO_TransferMode)); + assert_param(IS_SDIO_DPSM(SDIO_DataInitStruct->SDIO_DPSM)); + +/*---------------------------- SDIO DTIMER Configuration ---------------------*/ + /* Set the SDIO Data TimeOut value */ + SDIO->DTIMER = SDIO_DataInitStruct->SDIO_DataTimeOut; + +/*---------------------------- SDIO DLEN Configuration -----------------------*/ + /* Set the SDIO DataLength value */ + SDIO->DLEN = SDIO_DataInitStruct->SDIO_DataLength; + +/*---------------------------- SDIO DCTRL Configuration ----------------------*/ + /* Get the SDIO DCTRL value */ + tmpreg = SDIO->DCTRL; + /* Clear DEN, DTMODE, DTDIR and DBCKSIZE bits */ + tmpreg &= DCTRL_CLEAR_MASK; + /* Set DEN bit according to SDIO_DPSM value */ + /* Set DTMODE bit according to SDIO_TransferMode value */ + /* Set DTDIR bit according to SDIO_TransferDir value */ + /* Set DBCKSIZE bits according to SDIO_DataBlockSize value */ + tmpreg |= (uint32_t)SDIO_DataInitStruct->SDIO_DataBlockSize | SDIO_DataInitStruct->SDIO_TransferDir + | SDIO_DataInitStruct->SDIO_TransferMode | SDIO_DataInitStruct->SDIO_DPSM; + + /* Write to SDIO DCTRL */ + SDIO->DCTRL = tmpreg; +} + +/** + * @brief Fills each SDIO_DataInitStruct member with its default value. + * @param SDIO_DataInitStruct: pointer to an SDIO_DataInitTypeDef structure which + * will be initialized. + * @retval None + */ +void SDIO_DataStructInit(SDIO_DataInitTypeDef* SDIO_DataInitStruct) +{ + /* SDIO_DataInitStruct members default value */ + SDIO_DataInitStruct->SDIO_DataTimeOut = 0xFFFFFFFF; + SDIO_DataInitStruct->SDIO_DataLength = 0x00; + SDIO_DataInitStruct->SDIO_DataBlockSize = SDIO_DataBlockSize_1b; + SDIO_DataInitStruct->SDIO_TransferDir = SDIO_TransferDir_ToCard; + SDIO_DataInitStruct->SDIO_TransferMode = SDIO_TransferMode_Block; + SDIO_DataInitStruct->SDIO_DPSM = SDIO_DPSM_Disable; +} + +/** + * @brief Returns number of remaining data bytes to be transferred. + * @param None + * @retval Number of remaining data bytes to be transferred + */ +uint32_t SDIO_GetDataCounter(void) +{ + return SDIO->DCOUNT; +} + +/** + * @brief Read one data word from Rx FIFO. + * @param None + * @retval Data received + */ +uint32_t SDIO_ReadData(void) +{ + return SDIO->FIFO; +} + +/** + * @brief Write one data word to Tx FIFO. + * @param Data: 32-bit data word to write. + * @retval None + */ +void SDIO_WriteData(uint32_t Data) +{ + SDIO->FIFO = Data; +} + +/** + * @brief Returns the number of words left to be written to or read from FIFO. + * @param None + * @retval Remaining number of words. + */ +uint32_t SDIO_GetFIFOCount(void) +{ + return SDIO->FIFOCNT; +} + +/** + * @brief Starts the SD I/O Read Wait operation. + * @param NewState: new state of the Start SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StartSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTART_BB = (uint32_t) NewState; +} + +/** + * @brief Stops the SD I/O Read Wait operation. + * @param NewState: new state of the Stop SDIO Read Wait operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_StopSDIOReadWait(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_RWSTOP_BB = (uint32_t) NewState; +} + +/** + * @brief Sets one of the two options of inserting read wait interval. + * @param SDIO_ReadWaitMode: SD I/O Read Wait operation mode. + * This parameter can be: + * @arg SDIO_ReadWaitMode_CLK: Read Wait control by stopping SDIOCLK + * @arg SDIO_ReadWaitMode_DATA2: Read Wait control using SDIO_DATA2 + * @retval None + */ +void SDIO_SetSDIOReadWaitMode(uint32_t SDIO_ReadWaitMode) +{ + /* Check the parameters */ + assert_param(IS_SDIO_READWAIT_MODE(SDIO_ReadWaitMode)); + + *(__IO uint32_t *) DCTRL_RWMOD_BB = SDIO_ReadWaitMode; +} + +/** + * @brief Enables or disables the SD I/O Mode Operation. + * @param NewState: new state of SDIO specific operation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SetSDIOOperation(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) DCTRL_SDIOEN_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the SD I/O Mode suspend command sending. + * @param NewState: new state of the SD I/O Mode suspend command. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendSDIOSuspendCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_SDIOSUSPEND_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the command completion signal. + * @param NewState: new state of command completion signal. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CommandCompletionCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ENCMDCOMPL_BB = (uint32_t)NewState; +} + +/** + * @brief Enables or disables the CE-ATA interrupt. + * @param NewState: new state of CE-ATA interrupt. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_CEATAITCmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)((~((uint32_t)NewState)) & ((uint32_t)0x1)); +} + +/** + * @brief Sends CE-ATA command (CMD61). + * @param NewState: new state of CE-ATA command. This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SDIO_SendCEATACmd(FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + *(__IO uint32_t *) CMD_ATACMD_BB = (uint32_t)NewState; +} + +/** + * @brief Checks whether the specified SDIO flag is set or not. + * @param SDIO_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode. + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_CMDACT: Command transfer in progress + * @arg SDIO_FLAG_TXACT: Data transmit in progress + * @arg SDIO_FLAG_RXACT: Data receive in progress + * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty + * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full + * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full + * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full + * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty + * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty + * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO + * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval The new state of SDIO_FLAG (SET or RESET). + */ +FlagStatus SDIO_GetFlagStatus(uint32_t SDIO_FLAG) +{ + FlagStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_FLAG(SDIO_FLAG)); + + if ((SDIO->STA & SDIO_FLAG) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's pending flags. + * @param SDIO_FLAG: specifies the flag to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) + * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) + * @arg SDIO_FLAG_CTIMEOUT: Command response timeout + * @arg SDIO_FLAG_DTIMEOUT: Data timeout + * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error + * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error + * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) + * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) + * @arg SDIO_FLAG_DATAEND: Data end (data counter, SDIDCOUNT, is zero) + * @arg SDIO_FLAG_STBITERR: Start bit not detected on all data signals in wide + * bus mode + * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) + * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received + * @arg SDIO_FLAG_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearFlag(uint32_t SDIO_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_FLAG(SDIO_FLAG)); + + SDIO->ICR = SDIO_FLAG; +} + +/** + * @brief Checks whether the specified SDIO interrupt has occurred or not. + * @param SDIO_IT: specifies the SDIO interrupt source to check. + * This parameter can be one of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt + * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt + * @arg SDIO_IT_TXACT: Data transmit in progress interrupt + * @arg SDIO_IT_RXACT: Data receive in progress interrupt + * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt + * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt + * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt + * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt + * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt + * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt + * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt + * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 interrupt + * @retval The new state of SDIO_IT (SET or RESET). + */ +ITStatus SDIO_GetITStatus(uint32_t SDIO_IT) +{ + ITStatus bitstatus = RESET; + + /* Check the parameters */ + assert_param(IS_SDIO_GET_IT(SDIO_IT)); + if ((SDIO->STA & SDIO_IT) != (uint32_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the SDIO's interrupt pending bits. + * @param SDIO_IT: specifies the interrupt pending bit to clear. + * This parameter can be one or a combination of the following values: + * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt + * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt + * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt + * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt + * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt + * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt + * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt + * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt + * @arg SDIO_IT_DATAEND: Data end (data counter, SDIDCOUNT, is zero) interrupt + * @arg SDIO_IT_STBITERR: Start bit not detected on all data signals in wide + * bus mode interrupt + * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt + * @arg SDIO_IT_CEATAEND: CE-ATA command completion signal received for CMD61 + * @retval None + */ +void SDIO_ClearITPendingBit(uint32_t SDIO_IT) +{ + /* Check the parameters */ + assert_param(IS_SDIO_CLEAR_IT(SDIO_IT)); + + SDIO->ICR = SDIO_IT; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c new file mode 100755 index 0000000000..51a9cce773 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_spi.c @@ -0,0 +1,908 @@ +/** + ****************************************************************************** + * @file stm32f10x_spi.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the SPI firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_spi.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup SPI + * @brief SPI driver modules + * @{ + */ + +/** @defgroup SPI_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + + +/** @defgroup SPI_Private_Defines + * @{ + */ + +/* SPI SPE mask */ +#define CR1_SPE_Set ((uint16_t)0x0040) +#define CR1_SPE_Reset ((uint16_t)0xFFBF) + +/* I2S I2SE mask */ +#define I2SCFGR_I2SE_Set ((uint16_t)0x0400) +#define I2SCFGR_I2SE_Reset ((uint16_t)0xFBFF) + +/* SPI CRCNext mask */ +#define CR1_CRCNext_Set ((uint16_t)0x1000) + +/* SPI CRCEN mask */ +#define CR1_CRCEN_Set ((uint16_t)0x2000) +#define CR1_CRCEN_Reset ((uint16_t)0xDFFF) + +/* SPI SSOE mask */ +#define CR2_SSOE_Set ((uint16_t)0x0004) +#define CR2_SSOE_Reset ((uint16_t)0xFFFB) + +/* SPI registers Masks */ +#define CR1_CLEAR_Mask ((uint16_t)0x3040) +#define I2SCFGR_CLEAR_Mask ((uint16_t)0xF040) + +/* SPI or I2S mode selection masks */ +#define SPI_Mode_Select ((uint16_t)0xF7FF) +#define I2S_Mode_Select ((uint16_t)0x0800) + +/* I2S clock source selection masks */ +#define I2S2_CLOCK_SRC ((uint32_t)(0x00020000)) +#define I2S3_CLOCK_SRC ((uint32_t)(0x00040000)) +#define I2S_MUL_MASK ((uint32_t)(0x0000F000)) +#define I2S_DIV_MASK ((uint32_t)(0x000000F0)) + +/** + * @} + */ + +/** @defgroup SPI_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup SPI_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the SPIx peripheral registers to their default + * reset values (Affects also the I2Ss). + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_I2S_DeInit(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + if (SPIx == SPI1) + { + /* Enable SPI1 reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE); + /* Release SPI1 from reset state */ + RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, DISABLE); + } + else if (SPIx == SPI2) + { + /* Enable SPI2 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE); + /* Release SPI2 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, DISABLE); + } + else + { + if (SPIx == SPI3) + { + /* Enable SPI3 reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE); + /* Release SPI3 from reset state */ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, DISABLE); + } + } +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the SPI_InitStruct. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_InitStruct: pointer to a SPI_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral. + * @retval None + */ +void SPI_Init(SPI_TypeDef* SPIx, SPI_InitTypeDef* SPI_InitStruct) +{ + uint16_t tmpreg = 0; + + /* check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Check the SPI parameters */ + assert_param(IS_SPI_DIRECTION_MODE(SPI_InitStruct->SPI_Direction)); + assert_param(IS_SPI_MODE(SPI_InitStruct->SPI_Mode)); + assert_param(IS_SPI_DATASIZE(SPI_InitStruct->SPI_DataSize)); + assert_param(IS_SPI_CPOL(SPI_InitStruct->SPI_CPOL)); + assert_param(IS_SPI_CPHA(SPI_InitStruct->SPI_CPHA)); + assert_param(IS_SPI_NSS(SPI_InitStruct->SPI_NSS)); + assert_param(IS_SPI_BAUDRATE_PRESCALER(SPI_InitStruct->SPI_BaudRatePrescaler)); + assert_param(IS_SPI_FIRST_BIT(SPI_InitStruct->SPI_FirstBit)); + assert_param(IS_SPI_CRC_POLYNOMIAL(SPI_InitStruct->SPI_CRCPolynomial)); + +/*---------------------------- SPIx CR1 Configuration ------------------------*/ + /* Get the SPIx CR1 value */ + tmpreg = SPIx->CR1; + /* Clear BIDIMode, BIDIOE, RxONLY, SSM, SSI, LSBFirst, BR, MSTR, CPOL and CPHA bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure SPIx: direction, NSS management, first transmitted bit, BaudRate prescaler + master/salve mode, CPOL and CPHA */ + /* Set BIDImode, BIDIOE and RxONLY bits according to SPI_Direction value */ + /* Set SSM, SSI and MSTR bits according to SPI_Mode and SPI_NSS values */ + /* Set LSBFirst bit according to SPI_FirstBit value */ + /* Set BR bits according to SPI_BaudRatePrescaler value */ + /* Set CPOL bit according to SPI_CPOL value */ + /* Set CPHA bit according to SPI_CPHA value */ + tmpreg |= (uint16_t)((uint32_t)SPI_InitStruct->SPI_Direction | SPI_InitStruct->SPI_Mode | + SPI_InitStruct->SPI_DataSize | SPI_InitStruct->SPI_CPOL | + SPI_InitStruct->SPI_CPHA | SPI_InitStruct->SPI_NSS | + SPI_InitStruct->SPI_BaudRatePrescaler | SPI_InitStruct->SPI_FirstBit); + /* Write to SPIx CR1 */ + SPIx->CR1 = tmpreg; + + /* Activate the SPI mode (Reset I2SMOD bit in I2SCFGR register) */ + SPIx->I2SCFGR &= SPI_Mode_Select; + +/*---------------------------- SPIx CRCPOLY Configuration --------------------*/ + /* Write to SPIx CRCPOLY */ + SPIx->CRCPR = SPI_InitStruct->SPI_CRCPolynomial; +} + +/** + * @brief Initializes the SPIx peripheral according to the specified + * parameters in the I2S_InitStruct. + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral + * (configured in I2S mode). + * @param I2S_InitStruct: pointer to an I2S_InitTypeDef structure that + * contains the configuration information for the specified SPI peripheral + * configured in I2S mode. + * @note + * The function calculates the optimal prescaler needed to obtain the most + * accurate audio frequency (depending on the I2S clock source, the PLL values + * and the product configuration). But in case the prescaler value is greater + * than 511, the default value (0x02) will be configured instead. * + * @retval None + */ +void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct) +{ + uint16_t tmpreg = 0, i2sdiv = 2, i2sodd = 0, packetlength = 1; + uint32_t tmp = 0; + RCC_ClocksTypeDef RCC_Clocks; + uint32_t sourceclock = 0; + + /* Check the I2S parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_I2S_MODE(I2S_InitStruct->I2S_Mode)); + assert_param(IS_I2S_STANDARD(I2S_InitStruct->I2S_Standard)); + assert_param(IS_I2S_DATA_FORMAT(I2S_InitStruct->I2S_DataFormat)); + assert_param(IS_I2S_MCLK_OUTPUT(I2S_InitStruct->I2S_MCLKOutput)); + assert_param(IS_I2S_AUDIO_FREQ(I2S_InitStruct->I2S_AudioFreq)); + assert_param(IS_I2S_CPOL(I2S_InitStruct->I2S_CPOL)); + +/*----------------------- SPIx I2SCFGR & I2SPR Configuration -----------------*/ + /* Clear I2SMOD, I2SE, I2SCFG, PCMSYNC, I2SSTD, CKPOL, DATLEN and CHLEN bits */ + SPIx->I2SCFGR &= I2SCFGR_CLEAR_Mask; + SPIx->I2SPR = 0x0002; + + /* Get the I2SCFGR register value */ + tmpreg = SPIx->I2SCFGR; + + /* If the default value has to be written, reinitialize i2sdiv and i2sodd*/ + if(I2S_InitStruct->I2S_AudioFreq == I2S_AudioFreq_Default) + { + i2sodd = (uint16_t)0; + i2sdiv = (uint16_t)2; + } + /* If the requested audio frequency is not the default, compute the prescaler */ + else + { + /* Check the frame length (For the Prescaler computing) */ + if(I2S_InitStruct->I2S_DataFormat == I2S_DataFormat_16b) + { + /* Packet length is 16 bits */ + packetlength = 1; + } + else + { + /* Packet length is 32 bits */ + packetlength = 2; + } + + /* Get the I2S clock source mask depending on the peripheral number */ + if(((uint32_t)SPIx) == SPI2_BASE) + { + /* The mask is relative to I2S2 */ + tmp = I2S2_CLOCK_SRC; + } + else + { + /* The mask is relative to I2S3 */ + tmp = I2S3_CLOCK_SRC; + } + + /* Check the I2S clock source configuration depending on the Device: + Only Connectivity line devices have the PLL3 VCO clock */ +#ifdef STM32F10X_CL + if((RCC->CFGR2 & tmp) != 0) + { + /* Get the configuration bits of RCC PLL3 multiplier */ + tmp = (uint32_t)((RCC->CFGR2 & I2S_MUL_MASK) >> 12); + + /* Get the value of the PLL3 multiplier */ + if((tmp > 5) && (tmp < 15)) + { + /* Multiplier is between 8 and 14 (value 15 is forbidden) */ + tmp += 2; + } + else + { + if (tmp == 15) + { + /* Multiplier is 20 */ + tmp = 20; + } + } + /* Get the PREDIV2 value */ + sourceclock = (uint32_t)(((RCC->CFGR2 & I2S_DIV_MASK) >> 4) + 1); + + /* Calculate the Source Clock frequency based on PLL3 and PREDIV2 values */ + sourceclock = (uint32_t) ((HSE_Value / sourceclock) * tmp * 2); + } + else + { + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; + } +#else /* STM32F10X_HD */ + /* I2S Clock source is System clock: Get System Clock frequency */ + RCC_GetClocksFreq(&RCC_Clocks); + + /* Get the source clock value: based on System Clock value */ + sourceclock = RCC_Clocks.SYSCLK_Frequency; +#endif /* STM32F10X_CL */ + + /* Compute the Real divider depending on the MCLK output state with a floating point */ + if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable) + { + /* MCLK output is enabled */ + tmp = (uint16_t)(((((sourceclock / 256) * 10) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + else + { + /* MCLK output is disabled */ + tmp = (uint16_t)(((((sourceclock / (32 * packetlength)) *10 ) / I2S_InitStruct->I2S_AudioFreq)) + 5); + } + + /* Remove the floating point */ + tmp = tmp / 10; + + /* Check the parity of the divider */ + i2sodd = (uint16_t)(tmp & (uint16_t)0x0001); + + /* Compute the i2sdiv prescaler */ + i2sdiv = (uint16_t)((tmp - i2sodd) / 2); + + /* Get the Mask for the Odd bit (SPI_I2SPR[8]) register */ + i2sodd = (uint16_t) (i2sodd << 8); + } + + /* Test if the divider is 1 or 0 or greater than 0xFF */ + if ((i2sdiv < 2) || (i2sdiv > 0xFF)) + { + /* Set the default values */ + i2sdiv = 2; + i2sodd = 0; + } + + /* Write to SPIx I2SPR register the computed value */ + SPIx->I2SPR = (uint16_t)(i2sdiv | (uint16_t)(i2sodd | (uint16_t)I2S_InitStruct->I2S_MCLKOutput)); + + /* Configure the I2S with the SPI_InitStruct values */ + tmpreg |= (uint16_t)(I2S_Mode_Select | (uint16_t)(I2S_InitStruct->I2S_Mode | \ + (uint16_t)(I2S_InitStruct->I2S_Standard | (uint16_t)(I2S_InitStruct->I2S_DataFormat | \ + (uint16_t)I2S_InitStruct->I2S_CPOL)))); + + /* Write to SPIx I2SCFGR */ + SPIx->I2SCFGR = tmpreg; +} + +/** + * @brief Fills each SPI_InitStruct member with its default value. + * @param SPI_InitStruct : pointer to a SPI_InitTypeDef structure which will be initialized. + * @retval None + */ +void SPI_StructInit(SPI_InitTypeDef* SPI_InitStruct) +{ +/*--------------- Reset SPI init structure parameters values -----------------*/ + /* Initialize the SPI_Direction member */ + SPI_InitStruct->SPI_Direction = SPI_Direction_2Lines_FullDuplex; + /* initialize the SPI_Mode member */ + SPI_InitStruct->SPI_Mode = SPI_Mode_Slave; + /* initialize the SPI_DataSize member */ + SPI_InitStruct->SPI_DataSize = SPI_DataSize_8b; + /* Initialize the SPI_CPOL member */ + SPI_InitStruct->SPI_CPOL = SPI_CPOL_Low; + /* Initialize the SPI_CPHA member */ + SPI_InitStruct->SPI_CPHA = SPI_CPHA_1Edge; + /* Initialize the SPI_NSS member */ + SPI_InitStruct->SPI_NSS = SPI_NSS_Hard; + /* Initialize the SPI_BaudRatePrescaler member */ + SPI_InitStruct->SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2; + /* Initialize the SPI_FirstBit member */ + SPI_InitStruct->SPI_FirstBit = SPI_FirstBit_MSB; + /* Initialize the SPI_CRCPolynomial member */ + SPI_InitStruct->SPI_CRCPolynomial = 7; +} + +/** + * @brief Fills each I2S_InitStruct member with its default value. + * @param I2S_InitStruct : pointer to a I2S_InitTypeDef structure which will be initialized. + * @retval None + */ +void I2S_StructInit(I2S_InitTypeDef* I2S_InitStruct) +{ +/*--------------- Reset I2S init structure parameters values -----------------*/ + /* Initialize the I2S_Mode member */ + I2S_InitStruct->I2S_Mode = I2S_Mode_SlaveTx; + + /* Initialize the I2S_Standard member */ + I2S_InitStruct->I2S_Standard = I2S_Standard_Phillips; + + /* Initialize the I2S_DataFormat member */ + I2S_InitStruct->I2S_DataFormat = I2S_DataFormat_16b; + + /* Initialize the I2S_MCLKOutput member */ + I2S_InitStruct->I2S_MCLKOutput = I2S_MCLKOutput_Disable; + + /* Initialize the I2S_AudioFreq member */ + I2S_InitStruct->I2S_AudioFreq = I2S_AudioFreq_Default; + + /* Initialize the I2S_CPOL member */ + I2S_InitStruct->I2S_CPOL = I2S_CPOL_Low; +} + +/** + * @brief Enables or disables the specified SPI peripheral. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral */ + SPIx->CR1 |= CR1_SPE_Set; + } + else + { + /* Disable the selected SPI peripheral */ + SPIx->CR1 &= CR1_SPE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI peripheral (in I2S mode). + * @param SPIx: where x can be 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void I2S_Cmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_23_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR |= I2SCFGR_I2SE_Set; + } + else + { + /* Disable the selected SPI peripheral (in I2S mode) */ + SPIx->I2SCFGR &= I2SCFGR_I2SE_Reset; + } +} + +/** + * @brief Enables or disables the specified SPI/I2S interrupts. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to be enabled or disabled. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Tx buffer empty interrupt mask + * @arg SPI_I2S_IT_RXNE: Rx buffer not empty interrupt mask + * @arg SPI_I2S_IT_ERR: Error interrupt mask + * @param NewState: new state of the specified SPI/I2S interrupt. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_ITConfig(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT, FunctionalState NewState) +{ + uint16_t itpos = 0, itmask = 0 ; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_CONFIG_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = (uint16_t)1 << (uint16_t)itpos; + + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S interrupt */ + SPIx->CR2 |= itmask; + } + else + { + /* Disable the selected SPI/I2S interrupt */ + SPIx->CR2 &= (uint16_t)~itmask; + } +} + +/** + * @brief Enables or disables the SPIx/I2Sx DMA interface. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_DMAReq: specifies the SPI/I2S DMA transfer request to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg SPI_I2S_DMAReq_Tx: Tx buffer DMA transfer request + * @arg SPI_I2S_DMAReq_Rx: Rx buffer DMA transfer request + * @param NewState: new state of the selected SPI/I2S DMA transfer request. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_I2S_DMACmd(SPI_TypeDef* SPIx, uint16_t SPI_I2S_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + assert_param(IS_SPI_I2S_DMAREQ(SPI_I2S_DMAReq)); + if (NewState != DISABLE) + { + /* Enable the selected SPI/I2S DMA requests */ + SPIx->CR2 |= SPI_I2S_DMAReq; + } + else + { + /* Disable the selected SPI/I2S DMA requests */ + SPIx->CR2 &= (uint16_t)~SPI_I2S_DMAReq; + } +} + +/** + * @brief Transmits a Data through the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param Data : Data to be transmitted. + * @retval None + */ +void SPI_I2S_SendData(SPI_TypeDef* SPIx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Write in the DR register the data to be sent */ + SPIx->DR = Data; +} + +/** + * @brief Returns the most recent received data by the SPIx/I2Sx peripheral. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @retval The value of the received data. + */ +uint16_t SPI_I2S_ReceiveData(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the data in the DR register */ + return SPIx->DR; +} + +/** + * @brief Configures internally by software the NSS pin for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_NSSInternalSoft: specifies the SPI NSS internal state. + * This parameter can be one of the following values: + * @arg SPI_NSSInternalSoft_Set: Set NSS pin internally + * @arg SPI_NSSInternalSoft_Reset: Reset NSS pin internally + * @retval None + */ +void SPI_NSSInternalSoftwareConfig(SPI_TypeDef* SPIx, uint16_t SPI_NSSInternalSoft) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_NSS_INTERNAL(SPI_NSSInternalSoft)); + if (SPI_NSSInternalSoft != SPI_NSSInternalSoft_Reset) + { + /* Set NSS pin internally by software */ + SPIx->CR1 |= SPI_NSSInternalSoft_Set; + } + else + { + /* Reset NSS pin internally by software */ + SPIx->CR1 &= SPI_NSSInternalSoft_Reset; + } +} + +/** + * @brief Enables or disables the SS output for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx SS output. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_SSOutputCmd(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI SS output */ + SPIx->CR2 |= CR2_SSOE_Set; + } + else + { + /* Disable the selected SPI SS output */ + SPIx->CR2 &= CR2_SSOE_Reset; + } +} + +/** + * @brief Configures the data size for the selected SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_DataSize: specifies the SPI data size. + * This parameter can be one of the following values: + * @arg SPI_DataSize_16b: Set data frame format to 16bit + * @arg SPI_DataSize_8b: Set data frame format to 8bit + * @retval None + */ +void SPI_DataSizeConfig(SPI_TypeDef* SPIx, uint16_t SPI_DataSize) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DATASIZE(SPI_DataSize)); + /* Clear DFF bit */ + SPIx->CR1 &= (uint16_t)~SPI_DataSize_16b; + /* Set new DFF bit value */ + SPIx->CR1 |= SPI_DataSize; +} + +/** + * @brief Transmit the SPIx CRC value. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval None + */ +void SPI_TransmitCRC(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Enable the selected SPI CRC transmission */ + SPIx->CR1 |= CR1_CRCNext_Set; +} + +/** + * @brief Enables or disables the CRC value calculation of the transferred bytes. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param NewState: new state of the SPIx CRC value calculation. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void SPI_CalculateCRC(SPI_TypeDef* SPIx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the selected SPI CRC calculation */ + SPIx->CR1 |= CR1_CRCEN_Set; + } + else + { + /* Disable the selected SPI CRC calculation */ + SPIx->CR1 &= CR1_CRCEN_Reset; + } +} + +/** + * @brief Returns the transmit or the receive CRC register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_CRC: specifies the CRC register to be read. + * This parameter can be one of the following values: + * @arg SPI_CRC_Tx: Selects Tx CRC register + * @arg SPI_CRC_Rx: Selects Rx CRC register + * @retval The selected CRC register value.. + */ +uint16_t SPI_GetCRC(SPI_TypeDef* SPIx, uint8_t SPI_CRC) +{ + uint16_t crcreg = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_CRC(SPI_CRC)); + if (SPI_CRC != SPI_CRC_Rx) + { + /* Get the Tx CRC register */ + crcreg = SPIx->TXCRCR; + } + else + { + /* Get the Rx CRC register */ + crcreg = SPIx->RXCRCR; + } + /* Return the selected CRC register */ + return crcreg; +} + +/** + * @brief Returns the CRC Polynomial register value for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @retval The CRC Polynomial register value. + */ +uint16_t SPI_GetCRCPolynomial(SPI_TypeDef* SPIx) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + + /* Return the CRC polynomial register */ + return SPIx->CRCPR; +} + +/** + * @brief Selects the data transfer direction in bi-directional mode for the specified SPI. + * @param SPIx: where x can be 1, 2 or 3 to select the SPI peripheral. + * @param SPI_Direction: specifies the data transfer direction in bi-directional mode. + * This parameter can be one of the following values: + * @arg SPI_Direction_Tx: Selects Tx transmission direction + * @arg SPI_Direction_Rx: Selects Rx receive direction + * @retval None + */ +void SPI_BiDirectionalLineConfig(SPI_TypeDef* SPIx, uint16_t SPI_Direction) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_DIRECTION(SPI_Direction)); + if (SPI_Direction == SPI_Direction_Tx) + { + /* Set the Tx only mode */ + SPIx->CR1 |= SPI_Direction_Tx; + } + else + { + /* Set the Rx only mode */ + SPIx->CR1 &= SPI_Direction_Rx; + } +} + +/** + * @brief Checks whether the specified SPI/I2S flag is set or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_FLAG: specifies the SPI/I2S flag to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_FLAG_TXE: Transmit buffer empty flag. + * @arg SPI_I2S_FLAG_RXNE: Receive buffer not empty flag. + * @arg SPI_I2S_FLAG_BSY: Busy flag. + * @arg SPI_I2S_FLAG_OVR: Overrun flag. + * @arg SPI_FLAG_MODF: Mode Fault flag. + * @arg SPI_FLAG_CRCERR: CRC Error flag. + * @arg I2S_FLAG_UDR: Underrun Error flag. + * @arg I2S_FLAG_CHSIDE: Channel Side flag. + * @retval The new state of SPI_I2S_FLAG (SET or RESET). + */ +FlagStatus SPI_I2S_GetFlagStatus(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_FLAG(SPI_I2S_FLAG)); + /* Check the status of the specified SPI/I2S flag */ + if ((SPIx->SR & SPI_I2S_FLAG) != (uint16_t)RESET) + { + /* SPI_I2S_FLAG is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_FLAG is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_FLAG status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) flag. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_FLAG: specifies the SPI flag to clear. + * This function clears only CRCERR flag. + * @note + * - OVR (OverRun error) flag is cleared by software sequence: a read + * operation to SPI_DR register (SPI_I2S_ReceiveData()) followed by a read + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()). + * - UDR (UnderRun error) flag is cleared by a read operation to + * SPI_SR register (SPI_I2S_GetFlagStatus()). + * - MODF (Mode Fault) flag is cleared by software sequence: a read/write + * operation to SPI_SR register (SPI_I2S_GetFlagStatus()) followed by a + * write operation to SPI_CR1 register (SPI_Cmd() to enable the SPI). + * @retval None + */ +void SPI_I2S_ClearFlag(SPI_TypeDef* SPIx, uint16_t SPI_I2S_FLAG) +{ + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_FLAG(SPI_I2S_FLAG)); + + /* Clear the selected SPI CRC Error (CRCERR) flag */ + SPIx->SR = (uint16_t)~SPI_I2S_FLAG; +} + +/** + * @brief Checks whether the specified SPI/I2S interrupt has occurred or not. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * - 2 or 3 in I2S mode + * @param SPI_I2S_IT: specifies the SPI/I2S interrupt source to check. + * This parameter can be one of the following values: + * @arg SPI_I2S_IT_TXE: Transmit buffer empty interrupt. + * @arg SPI_I2S_IT_RXNE: Receive buffer not empty interrupt. + * @arg SPI_I2S_IT_OVR: Overrun interrupt. + * @arg SPI_IT_MODF: Mode Fault interrupt. + * @arg SPI_IT_CRCERR: CRC Error interrupt. + * @arg I2S_IT_UDR: Underrun Error interrupt. + * @retval The new state of SPI_I2S_IT (SET or RESET). + */ +ITStatus SPI_I2S_GetITStatus(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itpos = 0, itmask = 0, enablestatus = 0; + + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_GET_IT(SPI_I2S_IT)); + + /* Get the SPI/I2S IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Get the SPI/I2S IT mask */ + itmask = SPI_I2S_IT >> 4; + + /* Set the IT mask */ + itmask = 0x01 << itmask; + + /* Get the SPI_I2S_IT enable bit status */ + enablestatus = (SPIx->CR2 & itmask) ; + + /* Check the status of the specified SPI/I2S interrupt */ + if (((SPIx->SR & itpos) != (uint16_t)RESET) && enablestatus) + { + /* SPI_I2S_IT is set */ + bitstatus = SET; + } + else + { + /* SPI_I2S_IT is reset */ + bitstatus = RESET; + } + /* Return the SPI_I2S_IT status */ + return bitstatus; +} + +/** + * @brief Clears the SPIx CRC Error (CRCERR) interrupt pending bit. + * @param SPIx: where x can be + * - 1, 2 or 3 in SPI mode + * @param SPI_I2S_IT: specifies the SPI interrupt pending bit to clear. + * This function clears only CRCERR interrupt pending bit. + * @note + * - OVR (OverRun Error) interrupt pending bit is cleared by software + * sequence: a read operation to SPI_DR register (SPI_I2S_ReceiveData()) + * followed by a read operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - UDR (UnderRun Error) interrupt pending bit is cleared by a read + * operation to SPI_SR register (SPI_I2S_GetITStatus()). + * - MODF (Mode Fault) interrupt pending bit is cleared by software sequence: + * a read/write operation to SPI_SR register (SPI_I2S_GetITStatus()) + * followed by a write operation to SPI_CR1 register (SPI_Cmd() to enable + * the SPI). + * @retval None + */ +void SPI_I2S_ClearITPendingBit(SPI_TypeDef* SPIx, uint8_t SPI_I2S_IT) +{ + uint16_t itpos = 0; + /* Check the parameters */ + assert_param(IS_SPI_ALL_PERIPH(SPIx)); + assert_param(IS_SPI_I2S_CLEAR_IT(SPI_I2S_IT)); + + /* Get the SPI IT index */ + itpos = 0x01 << (SPI_I2S_IT & 0x0F); + + /* Clear the selected SPI CRC Error (CRCERR) interrupt pending bit */ + SPIx->SR = (uint16_t)~itpos; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c new file mode 100755 index 0000000000..81c8484e39 --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c @@ -0,0 +1,2890 @@ +/** + ****************************************************************************** + * @file stm32f10x_tim.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the TIM firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_tim.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup TIM + * @brief TIM driver modules + * @{ + */ + +/** @defgroup TIM_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Defines + * @{ + */ + +/* ---------------------- TIM registers bit mask ------------------------ */ +#define SMCR_ETR_Mask ((uint16_t)0x00FF) +#define CCMR_Offset ((uint16_t)0x0018) +#define CCER_CCE_Set ((uint16_t)0x0001) +#define CCER_CCNE_Set ((uint16_t)0x0004) + +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter); +/** + * @} + */ + +/** @defgroup TIM_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup TIM_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the TIMx peripheral registers to their default reset values. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval None + */ +void TIM_DeInit(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + + if (TIMx == TIM1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM1, DISABLE); + } + else if (TIMx == TIM2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM2, DISABLE); + } + else if (TIMx == TIM3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM3, DISABLE); + } + else if (TIMx == TIM4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM4, DISABLE); + } + else if (TIMx == TIM5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM5, DISABLE); + } + else if (TIMx == TIM6) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM6, DISABLE); + } + else if (TIMx == TIM7) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM7, DISABLE); + } + else if (TIMx == TIM8) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM8, DISABLE); + } + else if (TIMx == TIM9) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM9, DISABLE); + } + else if (TIMx == TIM10) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM10, DISABLE); + } + else if (TIMx == TIM11) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM11, DISABLE); + } + else if (TIMx == TIM12) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM12, DISABLE); + } + else if (TIMx == TIM13) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM13, DISABLE); + } + else if (TIMx == TIM14) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_TIM14, DISABLE); + } + else if (TIMx == TIM15) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM15, DISABLE); + } + else if (TIMx == TIM16) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM16, DISABLE); + } + else + { + if (TIMx == TIM17) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_TIM17, DISABLE); + } + } +} + +/** + * @brief Initializes the TIMx Time Base Unit peripheral according to + * the specified parameters in the TIM_TimeBaseInitStruct. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_TimeBaseInitStruct: pointer to a TIM_TimeBaseInitTypeDef + * structure that contains the configuration information for the + * specified TIM peripheral. + * @retval None + */ +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + uint16_t tmpcr1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_TimeBaseInitStruct->TIM_CounterMode)); + assert_param(IS_TIM_CKD_DIV(TIM_TimeBaseInitStruct->TIM_ClockDivision)); + + tmpcr1 = TIMx->CR1; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM2) || (TIMx == TIM3)|| + (TIMx == TIM4) || (TIMx == TIM5)) + { + /* Select the Counter Mode */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_CounterMode; + } + + if((TIMx != TIM6) && (TIMx != TIM7)) + { + /* Set the clock division */ + tmpcr1 &= (uint16_t)(~((uint16_t)TIM_CR1_CKD)); + tmpcr1 |= (uint32_t)TIM_TimeBaseInitStruct->TIM_ClockDivision; + } + + TIMx->CR1 = tmpcr1; + + /* Set the Autoreload value */ + TIMx->ARR = TIM_TimeBaseInitStruct->TIM_Period ; + + /* Set the Prescaler value */ + TIMx->PSC = TIM_TimeBaseInitStruct->TIM_Prescaler; + + if ((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| (TIMx == TIM16) || (TIMx == TIM17)) + { + /* Set the Repetition Counter value */ + TIMx->RCR = TIM_TimeBaseInitStruct->TIM_RepetitionCounter; + } + + /* Generate an update event to reload the Prescaler and the Repetition counter + values immediately */ + TIMx->EGR = TIM_PSCReloadMode_Immediate; +} + +/** + * @brief Initializes the TIMx Channel1 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)(~(uint16_t)TIM_CCER_CC1E); + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare Mode Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC1M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC1S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1P)); + /* Set the Output Compare Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCPolarity; + + /* Set the Output State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputState; + + if((TIMx == TIM1) || (TIMx == TIM8)|| (TIMx == TIM15)|| + (TIMx == TIM16)|| (TIMx == TIM17)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NP)); + /* Set the Output N Polarity */ + tmpccer |= TIM_OCInitStruct->TIM_OCNPolarity; + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC1NE)); + /* Set the Output N State */ + tmpccer |= TIM_OCInitStruct->TIM_OutputNState; + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS1N)); + + /* Set the Output Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCIdleState; + /* Set the Output N Idle state */ + tmpcr2 |= TIM_OCInitStruct->TIM_OCNIdleState; + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR1 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel2 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC2E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR1 register value */ + tmpccmrx = TIMx->CCMR1; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_OC2M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 4); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 4); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 4); + + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC2NE)); + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 4); + + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS2N)); + + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 2); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 2); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR2 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel3 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC3E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC3M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC3S)); + /* Select the Output Compare Mode */ + tmpccmrx |= TIM_OCInitStruct->TIM_OCMode; + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 8); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 8); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OUTPUTN_STATE(TIM_OCInitStruct->TIM_OutputNState)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCInitStruct->TIM_OCNPolarity)); + assert_param(IS_TIM_OCNIDLE_STATE(TIM_OCInitStruct->TIM_OCNIdleState)); + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + + /* Reset the Output N Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NP)); + /* Set the Output N Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCNPolarity << 8); + /* Reset the Output N State */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC3NE)); + + /* Set the Output N State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputNState << 8); + /* Reset the Output Compare and Output Compare N IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3)); + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS3N)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 4); + /* Set the Output N Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCNIdleState << 4); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR3 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIMx Channel4 according to the specified + * parameters in the TIM_OCInitStruct. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCInitStruct: pointer to a TIM_OCInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_MODE(TIM_OCInitStruct->TIM_OCMode)); + assert_param(IS_TIM_OUTPUT_STATE(TIM_OCInitStruct->TIM_OutputState)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCInitStruct->TIM_OCPolarity)); + /* Disable the Channel 2: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)(~((uint16_t)TIM_CCER_CC4E)); + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + /* Get the TIMx CR2 register value */ + tmpcr2 = TIMx->CR2; + + /* Get the TIMx CCMR2 register value */ + tmpccmrx = TIMx->CCMR2; + + /* Reset the Output Compare mode and Capture/Compare selection Bits */ + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_OC4M)); + tmpccmrx &= (uint16_t)(~((uint16_t)TIM_CCMR2_CC4S)); + + /* Select the Output Compare Mode */ + tmpccmrx |= (uint16_t)(TIM_OCInitStruct->TIM_OCMode << 8); + + /* Reset the Output Polarity level */ + tmpccer &= (uint16_t)(~((uint16_t)TIM_CCER_CC4P)); + /* Set the Output Compare Polarity */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OCPolarity << 12); + + /* Set the Output State */ + tmpccer |= (uint16_t)(TIM_OCInitStruct->TIM_OutputState << 12); + + if((TIMx == TIM1) || (TIMx == TIM8)) + { + assert_param(IS_TIM_OCIDLE_STATE(TIM_OCInitStruct->TIM_OCIdleState)); + /* Reset the Output Compare IDLE State */ + tmpcr2 &= (uint16_t)(~((uint16_t)TIM_CR2_OIS4)); + /* Set the Output Idle state */ + tmpcr2 |= (uint16_t)(TIM_OCInitStruct->TIM_OCIdleState << 6); + } + /* Write to TIMx CR2 */ + TIMx->CR2 = tmpcr2; + + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmrx; + + /* Set the Capture Compare Register value */ + TIMx->CCR4 = TIM_OCInitStruct->TIM_Pulse; + + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Initializes the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); + assert_param(IS_TIM_IC_SELECTION(TIM_ICInitStruct->TIM_ICSelection)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICInitStruct->TIM_ICPrescaler)); + assert_param(IS_TIM_IC_FILTER(TIM_ICInitStruct->TIM_ICFilter)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + assert_param(IS_TIM_IC_POLARITY(TIM_ICInitStruct->TIM_ICPolarity)); + } + else + { + assert_param(IS_TIM_IC_POLARITY_LITE(TIM_ICInitStruct->TIM_ICPolarity)); + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_2) + { + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_3) + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI3 Configuration */ + TI3_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC3Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* TI4 Configuration */ + TI4_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, + TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC4Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the TIM peripheral according to the specified + * parameters in the TIM_ICInitStruct to measure an external PWM signal. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure + * that contains the configuration information for the specified TIM peripheral. + * @retval None + */ +void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + uint16_t icoppositepolarity = TIM_ICPolarity_Rising; + uint16_t icoppositeselection = TIM_ICSelection_DirectTI; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Select the Opposite Input Polarity */ + if (TIM_ICInitStruct->TIM_ICPolarity == TIM_ICPolarity_Rising) + { + icoppositepolarity = TIM_ICPolarity_Falling; + } + else + { + icoppositepolarity = TIM_ICPolarity_Rising; + } + /* Select the Opposite Input */ + if (TIM_ICInitStruct->TIM_ICSelection == TIM_ICSelection_DirectTI) + { + icoppositeselection = TIM_ICSelection_IndirectTI; + } + else + { + icoppositeselection = TIM_ICSelection_DirectTI; + } + if (TIM_ICInitStruct->TIM_Channel == TIM_Channel_1) + { + /* TI1 Configuration */ + TI1_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI2 Configuration */ + TI2_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } + else + { + /* TI2 Configuration */ + TI2_Config(TIMx, TIM_ICInitStruct->TIM_ICPolarity, TIM_ICInitStruct->TIM_ICSelection, + TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC2Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + /* TI1 Configuration */ + TI1_Config(TIMx, icoppositepolarity, icoppositeselection, TIM_ICInitStruct->TIM_ICFilter); + /* Set the Input Capture Prescaler value */ + TIM_SetIC1Prescaler(TIMx, TIM_ICInitStruct->TIM_ICPrescaler); + } +} + +/** + * @brief Configures the: Break feature, dead time, Lock level, the OSSI, + * the OSSR State and the AOE(automatic output enable). + * @param TIMx: where x can be 1 or 8 to select the TIM + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure that + * contains the BDTR Register configuration information for the TIM peripheral. + * @retval None + */ +void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OSSR_STATE(TIM_BDTRInitStruct->TIM_OSSRState)); + assert_param(IS_TIM_OSSI_STATE(TIM_BDTRInitStruct->TIM_OSSIState)); + assert_param(IS_TIM_LOCK_LEVEL(TIM_BDTRInitStruct->TIM_LOCKLevel)); + assert_param(IS_TIM_BREAK_STATE(TIM_BDTRInitStruct->TIM_Break)); + assert_param(IS_TIM_BREAK_POLARITY(TIM_BDTRInitStruct->TIM_BreakPolarity)); + assert_param(IS_TIM_AUTOMATIC_OUTPUT_STATE(TIM_BDTRInitStruct->TIM_AutomaticOutput)); + /* Set the Lock level, the Break enable Bit and the Ploarity, the OSSR State, + the OSSI State, the dead time value and the Automatic Output Enable Bit */ + TIMx->BDTR = (uint32_t)TIM_BDTRInitStruct->TIM_OSSRState | TIM_BDTRInitStruct->TIM_OSSIState | + TIM_BDTRInitStruct->TIM_LOCKLevel | TIM_BDTRInitStruct->TIM_DeadTime | + TIM_BDTRInitStruct->TIM_Break | TIM_BDTRInitStruct->TIM_BreakPolarity | + TIM_BDTRInitStruct->TIM_AutomaticOutput; +} + +/** + * @brief Fills each TIM_TimeBaseInitStruct member with its default value. + * @param TIM_TimeBaseInitStruct : pointer to a TIM_TimeBaseInitTypeDef + * structure which will be initialized. + * @retval None + */ +void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +{ + /* Set the default configuration */ + TIM_TimeBaseInitStruct->TIM_Period = 0xFFFF; + TIM_TimeBaseInitStruct->TIM_Prescaler = 0x0000; + TIM_TimeBaseInitStruct->TIM_ClockDivision = TIM_CKD_DIV1; + TIM_TimeBaseInitStruct->TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInitStruct->TIM_RepetitionCounter = 0x0000; +} + +/** + * @brief Fills each TIM_OCInitStruct member with its default value. + * @param TIM_OCInitStruct : pointer to a TIM_OCInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_OCStructInit(TIM_OCInitTypeDef* TIM_OCInitStruct) +{ + /* Set the default configuration */ + TIM_OCInitStruct->TIM_OCMode = TIM_OCMode_Timing; + TIM_OCInitStruct->TIM_OutputState = TIM_OutputState_Disable; + TIM_OCInitStruct->TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStruct->TIM_Pulse = 0x0000; + TIM_OCInitStruct->TIM_OCPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCNPolarity = TIM_OCPolarity_High; + TIM_OCInitStruct->TIM_OCIdleState = TIM_OCIdleState_Reset; + TIM_OCInitStruct->TIM_OCNIdleState = TIM_OCNIdleState_Reset; +} + +/** + * @brief Fills each TIM_ICInitStruct member with its default value. + * @param TIM_ICInitStruct: pointer to a TIM_ICInitTypeDef structure which will + * be initialized. + * @retval None + */ +void TIM_ICStructInit(TIM_ICInitTypeDef* TIM_ICInitStruct) +{ + /* Set the default configuration */ + TIM_ICInitStruct->TIM_Channel = TIM_Channel_1; + TIM_ICInitStruct->TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStruct->TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStruct->TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStruct->TIM_ICFilter = 0x00; +} + +/** + * @brief Fills each TIM_BDTRInitStruct member with its default value. + * @param TIM_BDTRInitStruct: pointer to a TIM_BDTRInitTypeDef structure which + * will be initialized. + * @retval None + */ +void TIM_BDTRStructInit(TIM_BDTRInitTypeDef* TIM_BDTRInitStruct) +{ + /* Set the default configuration */ + TIM_BDTRInitStruct->TIM_OSSRState = TIM_OSSRState_Disable; + TIM_BDTRInitStruct->TIM_OSSIState = TIM_OSSIState_Disable; + TIM_BDTRInitStruct->TIM_LOCKLevel = TIM_LOCKLevel_OFF; + TIM_BDTRInitStruct->TIM_DeadTime = 0x00; + TIM_BDTRInitStruct->TIM_Break = TIM_Break_Disable; + TIM_BDTRInitStruct->TIM_BreakPolarity = TIM_BreakPolarity_Low; + TIM_BDTRInitStruct->TIM_AutomaticOutput = TIM_AutomaticOutput_Disable; +} + +/** + * @brief Enables or disables the specified TIM peripheral. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param NewState: new state of the TIMx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_Cmd(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the TIM Counter */ + TIMx->CR1 |= TIM_CR1_CEN; + } + else + { + /* Disable the TIM Counter */ + TIMx->CR1 &= (uint16_t)(~((uint16_t)TIM_CR1_CEN)); + } +} + +/** + * @brief Enables or disables the TIM peripheral Main Outputs. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral. + * @param NewState: new state of the TIM peripheral Main Outputs. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CtrlPWMOutputs(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the TIM Main Output */ + TIMx->BDTR |= TIM_BDTR_MOE; + } + else + { + /* Disable the TIM Main Output */ + TIMx->BDTR &= (uint16_t)(~((uint16_t)TIM_BDTR_MOE)); + } +} + +/** + * @brief Enables or disables the specified TIM interrupts. + * @param TIMx: where x can be 1 to 17 to select the TIMx peripheral. + * @param TIM_IT: specifies the TIM interrupts sources to be enabled or disabled. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can only generate an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @param NewState: new state of the TIM interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ITConfig(TIM_TypeDef* TIMx, uint16_t TIM_IT, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Interrupt sources */ + TIMx->DIER |= TIM_IT; + } + else + { + /* Disable the Interrupt sources */ + TIMx->DIER &= (uint16_t)~TIM_IT; + } +} + +/** + * @brief Configures the TIMx event to be generate by software. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_EventSource: specifies the event source. + * This parameter can be one or more of the following values: + * @arg TIM_EventSource_Update: Timer update Event source + * @arg TIM_EventSource_CC1: Timer Capture Compare 1 Event source + * @arg TIM_EventSource_CC2: Timer Capture Compare 2 Event source + * @arg TIM_EventSource_CC3: Timer Capture Compare 3 Event source + * @arg TIM_EventSource_CC4: Timer Capture Compare 4 Event source + * @arg TIM_EventSource_COM: Timer COM event source + * @arg TIM_EventSource_Trigger: Timer Trigger Event source + * @arg TIM_EventSource_Break: Timer Break event source + * @note + * - TIM6 and TIM7 can only generate an update event. + * - TIM_EventSource_COM and TIM_EventSource_Break are used only with TIM1 and TIM8. + * @retval None + */ +void TIM_GenerateEvent(TIM_TypeDef* TIMx, uint16_t TIM_EventSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_EVENT_SOURCE(TIM_EventSource)); + + /* Set the event sources */ + TIMx->EGR = TIM_EventSource; +} + +/** + * @brief Configures the TIMx's DMA interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param TIM_DMABase: DMA Base address. + * This parameter can be one of the following values: + * @arg TIM_DMABase_CR, TIM_DMABase_CR2, TIM_DMABase_SMCR, + * TIM_DMABase_DIER, TIM1_DMABase_SR, TIM_DMABase_EGR, + * TIM_DMABase_CCMR1, TIM_DMABase_CCMR2, TIM_DMABase_CCER, + * TIM_DMABase_CNT, TIM_DMABase_PSC, TIM_DMABase_ARR, + * TIM_DMABase_RCR, TIM_DMABase_CCR1, TIM_DMABase_CCR2, + * TIM_DMABase_CCR3, TIM_DMABase_CCR4, TIM_DMABase_BDTR, + * TIM_DMABase_DCR. + * @param TIM_DMABurstLength: DMA Burst length. + * This parameter can be one value between: + * TIM_DMABurstLength_1Transfer and TIM_DMABurstLength_18Transfers. + * @retval None + */ +void TIM_DMAConfig(TIM_TypeDef* TIMx, uint16_t TIM_DMABase, uint16_t TIM_DMABurstLength) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_BASE(TIM_DMABase)); + assert_param(IS_TIM_DMA_LENGTH(TIM_DMABurstLength)); + /* Set the DMA Base and the DMA Burst Length */ + TIMx->DCR = TIM_DMABase | TIM_DMABurstLength; +} + +/** + * @brief Enables or disables the TIMx's DMA Requests. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 15, 16 or 17 + * to select the TIM peripheral. + * @param TIM_DMASource: specifies the DMA Request sources. + * This parameter can be any combination of the following values: + * @arg TIM_DMA_Update: TIM update Interrupt source + * @arg TIM_DMA_CC1: TIM Capture Compare 1 DMA source + * @arg TIM_DMA_CC2: TIM Capture Compare 2 DMA source + * @arg TIM_DMA_CC3: TIM Capture Compare 3 DMA source + * @arg TIM_DMA_CC4: TIM Capture Compare 4 DMA source + * @arg TIM_DMA_COM: TIM Commutation DMA source + * @arg TIM_DMA_Trigger: TIM Trigger DMA source + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST9_PERIPH(TIMx)); + assert_param(IS_TIM_DMA_SOURCE(TIM_DMASource)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the DMA sources */ + TIMx->DIER |= TIM_DMASource; + } + else + { + /* Disable the DMA sources */ + TIMx->DIER &= (uint16_t)~TIM_DMASource; + } +} + +/** + * @brief Configures the TIMx internal Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 + * to select the TIM peripheral. + * @retval None + */ +void TIM_InternalClockConfig(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Disable slave mode to clock the prescaler directly with the internal clock */ + TIMx->SMCR &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); +} + +/** + * @brief Configures the TIMx Internal Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ITRSource: Trigger source. + * This parameter can be one of the following values: + * @param TIM_TS_ITR0: Internal Trigger 0 + * @param TIM_TS_ITR1: Internal Trigger 1 + * @param TIM_TS_ITR2: Internal Trigger 2 + * @param TIM_TS_ITR3: Internal Trigger 3 + * @retval None + */ +void TIM_ITRxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_INTERNAL_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Select the Internal Trigger */ + TIM_SelectInputTrigger(TIMx, TIM_InputTriggerSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the TIMx Trigger as External Clock + * @param TIMx: where x can be 1, 2, 3, 4, 5, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TIxExternalCLKSource: Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TIxExternalCLK1Source_TI1ED: TI1 Edge Detector + * @arg TIM_TIxExternalCLK1Source_TI1: Filtered Timer Input 1 + * @arg TIM_TIxExternalCLK1Source_TI2: Filtered Timer Input 2 + * @param TIM_ICPolarity: specifies the TIx Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param ICFilter : specifies the filter value. + * This parameter must be a value between 0x0 and 0xF. + * @retval None + */ +void TIM_TIxExternalClockConfig(TIM_TypeDef* TIMx, uint16_t TIM_TIxExternalCLKSource, + uint16_t TIM_ICPolarity, uint16_t ICFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TIXCLK_SOURCE(TIM_TIxExternalCLKSource)); + assert_param(IS_TIM_IC_POLARITY(TIM_ICPolarity)); + assert_param(IS_TIM_IC_FILTER(ICFilter)); + /* Configure the Timer Input Clock Source */ + if (TIM_TIxExternalCLKSource == TIM_TIxExternalCLK1Source_TI2) + { + TI2_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + else + { + TI1_Config(TIMx, TIM_ICPolarity, TIM_ICSelection_DirectTI, ICFilter); + } + /* Select the Trigger source */ + TIM_SelectInputTrigger(TIMx, TIM_TIxExternalCLKSource); + /* Select the External clock mode1 */ + TIMx->SMCR |= TIM_SlaveMode_External1; +} + +/** + * @brief Configures the External clock Mode1 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode1Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the SMS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + /* Select the External clock mode1 */ + tmpsmcr |= TIM_SlaveMode_External1; + /* Select the Trigger selection : ETRF */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + tmpsmcr |= TIM_TS_ETRF; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the External clock Mode2 + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRClockMode2Config(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, + uint16_t TIM_ExtTRGPolarity, uint16_t ExtTRGFilter) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + /* Configure the ETR Clock source */ + TIM_ETRConfig(TIMx, TIM_ExtTRGPrescaler, TIM_ExtTRGPolarity, ExtTRGFilter); + /* Enable the External clock mode2 */ + TIMx->SMCR |= TIM_SMCR_ECE; +} + +/** + * @brief Configures the TIMx External Trigger (ETR). + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ExtTRGPrescaler: The external Trigger Prescaler. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPSC_OFF: ETRP Prescaler OFF. + * @arg TIM_ExtTRGPSC_DIV2: ETRP frequency divided by 2. + * @arg TIM_ExtTRGPSC_DIV4: ETRP frequency divided by 4. + * @arg TIM_ExtTRGPSC_DIV8: ETRP frequency divided by 8. + * @param TIM_ExtTRGPolarity: The external Trigger Polarity. + * This parameter can be one of the following values: + * @arg TIM_ExtTRGPolarity_Inverted: active low or falling edge active. + * @arg TIM_ExtTRGPolarity_NonInverted: active high or rising edge active. + * @param ExtTRGFilter: External Trigger Filter. + * This parameter must be a value between 0x00 and 0x0F + * @retval None + */ +void TIM_ETRConfig(TIM_TypeDef* TIMx, uint16_t TIM_ExtTRGPrescaler, uint16_t TIM_ExtTRGPolarity, + uint16_t ExtTRGFilter) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_EXT_PRESCALER(TIM_ExtTRGPrescaler)); + assert_param(IS_TIM_EXT_POLARITY(TIM_ExtTRGPolarity)); + assert_param(IS_TIM_EXT_FILTER(ExtTRGFilter)); + tmpsmcr = TIMx->SMCR; + /* Reset the ETR Bits */ + tmpsmcr &= SMCR_ETR_Mask; + /* Set the Prescaler, the Filter value and the Polarity */ + tmpsmcr |= (uint16_t)(TIM_ExtTRGPrescaler | (uint16_t)(TIM_ExtTRGPolarity | (uint16_t)(ExtTRGFilter << (uint16_t)8))); + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Prescaler. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Prescaler: specifies the Prescaler Register value + * @param TIM_PSCReloadMode: specifies the TIM Prescaler Reload mode + * This parameter can be one of the following values: + * @arg TIM_PSCReloadMode_Update: The Prescaler is loaded at the update event. + * @arg TIM_PSCReloadMode_Immediate: The Prescaler is loaded immediately. + * @retval None + */ +void TIM_PrescalerConfig(TIM_TypeDef* TIMx, uint16_t Prescaler, uint16_t TIM_PSCReloadMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_PRESCALER_RELOAD(TIM_PSCReloadMode)); + /* Set the Prescaler value */ + TIMx->PSC = Prescaler; + /* Set or reset the UG Bit */ + TIMx->EGR = TIM_PSCReloadMode; +} + +/** + * @brief Specifies the TIMx Counter Mode to be used. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_CounterMode: specifies the Counter Mode to be used + * This parameter can be one of the following values: + * @arg TIM_CounterMode_Up: TIM Up Counting Mode + * @arg TIM_CounterMode_Down: TIM Down Counting Mode + * @arg TIM_CounterMode_CenterAligned1: TIM Center Aligned Mode1 + * @arg TIM_CounterMode_CenterAligned2: TIM Center Aligned Mode2 + * @arg TIM_CounterMode_CenterAligned3: TIM Center Aligned Mode3 + * @retval None + */ +void TIM_CounterModeConfig(TIM_TypeDef* TIMx, uint16_t TIM_CounterMode) +{ + uint16_t tmpcr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_COUNTER_MODE(TIM_CounterMode)); + tmpcr1 = TIMx->CR1; + /* Reset the CMS and DIR Bits */ + tmpcr1 &= (uint16_t)(~((uint16_t)(TIM_CR1_DIR | TIM_CR1_CMS))); + /* Set the Counter Mode */ + tmpcr1 |= TIM_CounterMode; + /* Write to TIMx CR1 register */ + TIMx->CR1 = tmpcr1; +} + +/** + * @brief Selects the Input Trigger source + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_InputTriggerSource: The Input Trigger source. + * This parameter can be one of the following values: + * @arg TIM_TS_ITR0: Internal Trigger 0 + * @arg TIM_TS_ITR1: Internal Trigger 1 + * @arg TIM_TS_ITR2: Internal Trigger 2 + * @arg TIM_TS_ITR3: Internal Trigger 3 + * @arg TIM_TS_TI1F_ED: TI1 Edge Detector + * @arg TIM_TS_TI1FP1: Filtered Timer Input 1 + * @arg TIM_TS_TI2FP2: Filtered Timer Input 2 + * @arg TIM_TS_ETRF: External Trigger input + * @retval None + */ +void TIM_SelectInputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_InputTriggerSource) +{ + uint16_t tmpsmcr = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_TRIGGER_SELECTION(TIM_InputTriggerSource)); + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + /* Reset the TS Bits */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_TS)); + /* Set the Input Trigger source */ + tmpsmcr |= TIM_InputTriggerSource; + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; +} + +/** + * @brief Configures the TIMx Encoder Interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_EncoderMode: specifies the TIMx Encoder Mode. + * This parameter can be one of the following values: + * @arg TIM_EncoderMode_TI1: Counter counts on TI1FP1 edge depending on TI2FP2 level. + * @arg TIM_EncoderMode_TI2: Counter counts on TI2FP2 edge depending on TI1FP1 level. + * @arg TIM_EncoderMode_TI12: Counter counts on both TI1FP1 and TI2FP2 edges depending + * on the level of the other input. + * @param TIM_IC1Polarity: specifies the IC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @param TIM_IC2Polarity: specifies the IC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Falling: IC Falling edge. + * @arg TIM_ICPolarity_Rising: IC Rising edge. + * @retval None + */ +void TIM_EncoderInterfaceConfig(TIM_TypeDef* TIMx, uint16_t TIM_EncoderMode, + uint16_t TIM_IC1Polarity, uint16_t TIM_IC2Polarity) +{ + uint16_t tmpsmcr = 0; + uint16_t tmpccmr1 = 0; + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_TIM_ENCODER_MODE(TIM_EncoderMode)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC1Polarity)); + assert_param(IS_TIM_IC_POLARITY(TIM_IC2Polarity)); + + /* Get the TIMx SMCR register value */ + tmpsmcr = TIMx->SMCR; + + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + + /* Get the TIMx CCER register value */ + tmpccer = TIMx->CCER; + + /* Set the encoder Mode */ + tmpsmcr &= (uint16_t)(~((uint16_t)TIM_SMCR_SMS)); + tmpsmcr |= TIM_EncoderMode; + + /* Select the Capture Compare 1 and the Capture Compare 2 as input */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & (uint16_t)(~((uint16_t)TIM_CCMR1_CC2S))); + tmpccmr1 |= TIM_CCMR1_CC1S_0 | TIM_CCMR1_CC2S_0; + + /* Set the TI1 and the TI2 Polarities */ + tmpccer &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCER_CC1P)) & ((uint16_t)~((uint16_t)TIM_CCER_CC2P))); + tmpccer |= (uint16_t)(TIM_IC1Polarity | (uint16_t)(TIM_IC2Polarity << (uint16_t)4)); + + /* Write to TIMx SMCR */ + TIMx->SMCR = tmpsmcr; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; + /* Write to TIMx CCER */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Forces the TIMx output 1 waveform to active or inactive level. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC1REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC1REF. + * @retval None + */ +void TIM_ForcedOC1Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1M); + /* Configure The Forced output Mode */ + tmpccmr1 |= TIM_ForcedAction; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 2 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC2REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC2REF. + * @retval None + */ +void TIM_ForcedOC2Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2M Bits */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2M); + /* Configure The Forced output Mode */ + tmpccmr1 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Forces the TIMx output 3 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC3REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC3REF. + * @retval None + */ +void TIM_ForcedOC3Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC1M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3M); + /* Configure The Forced output Mode */ + tmpccmr2 |= TIM_ForcedAction; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Forces the TIMx output 4 waveform to active or inactive level. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ForcedAction: specifies the forced Action to be set to the output waveform. + * This parameter can be one of the following values: + * @arg TIM_ForcedAction_Active: Force active level on OC4REF + * @arg TIM_ForcedAction_InActive: Force inactive level on OC4REF. + * @retval None + */ +void TIM_ForcedOC4Config(TIM_TypeDef* TIMx, uint16_t TIM_ForcedAction) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_FORCED_ACTION(TIM_ForcedAction)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC2M Bits */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4M); + /* Configure The Forced output Mode */ + tmpccmr2 |= (uint16_t)(TIM_ForcedAction << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables TIMx peripheral Preload register on ARR. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx peripheral Preload register + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_ARRPreloadConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the ARR Preload Bit */ + TIMx->CR1 |= TIM_CR1_ARPE; + } + else + { + /* Reset the ARR Preload Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_ARPE); + } +} + +/** + * @brief Selects the TIM peripheral Commutation event. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIMx peripheral + * @param NewState: new state of the Commutation event. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCOM(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the COM Bit */ + TIMx->CR2 |= TIM_CR2_CCUS; + } + else + { + /* Reset the COM Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCUS); + } +} + +/** + * @brief Selects the TIMx peripheral Capture Compare DMA source. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 15, 16 or 17 to select + * the TIM peripheral. + * @param NewState: new state of the Capture Compare DMA source + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectCCDMA(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST4_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCDS Bit */ + TIMx->CR2 |= TIM_CR2_CCDS; + } + else + { + /* Reset the CCDS Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCDS); + } +} + +/** + * @brief Sets or Resets the TIM peripheral Capture Compare Preload Control bit. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8 or 15 + * to select the TIMx peripheral + * @param NewState: new state of the Capture Compare Preload Control bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_CCPreloadControl(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST5_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the CCPC Bit */ + TIMx->CR2 |= TIM_CR2_CCPC; + } + else + { + /* Reset the CCPC Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_CCPC); + } +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR1. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC1PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= TIM_OCPreload; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR2. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC2PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2PE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr1 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR3. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC3PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= TIM_OCPreload; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Enables or disables the TIMx peripheral Preload register on CCR4. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPreload: new state of the TIMx peripheral Preload register + * This parameter can be one of the following values: + * @arg TIM_OCPreload_Enable + * @arg TIM_OCPreload_Disable + * @retval None + */ +void TIM_OC4PreloadConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPreload) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCPRELOAD_STATE(TIM_OCPreload)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4PE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4PE); + /* Enable or Disable the Output Compare Preload feature */ + tmpccmr2 |= (uint16_t)(TIM_OCPreload << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 1 Fast feature. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC1FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC1FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= TIM_OCFast; + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 2 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select + * the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC2FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR1 register value */ + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2FE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR1 */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Configures the TIMx Output Compare 3 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC3FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= TIM_OCFast; + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx Output Compare 4 Fast feature. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCFast: new state of the Output Compare Fast Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCFast_Enable: TIM output compare fast enable + * @arg TIM_OCFast_Disable: TIM output compare fast disable + * @retval None + */ +void TIM_OC4FastConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCFast) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCFAST_STATE(TIM_OCFast)); + /* Get the TIMx CCMR2 register value */ + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4FE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4FE); + /* Enable or Disable the Output Compare Fast Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCFast << 8); + /* Write to TIMx CCMR2 */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF1 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC1Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + + tmpccmr1 = TIMx->CCMR1; + + /* Reset the OC1CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC1CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= TIM_OCClear; + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF2 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC2Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr1 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr1 = TIMx->CCMR1; + /* Reset the OC2CE Bit */ + tmpccmr1 &= (uint16_t)~((uint16_t)TIM_CCMR1_OC2CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr1 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR1 register */ + TIMx->CCMR1 = tmpccmr1; +} + +/** + * @brief Clears or safeguards the OCREF3 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC3Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC3CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC3CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= TIM_OCClear; + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Clears or safeguards the OCREF4 signal on an external event + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCClear: new state of the Output Compare Clear Enable Bit. + * This parameter can be one of the following values: + * @arg TIM_OCClear_Enable: TIM Output clear enable + * @arg TIM_OCClear_Disable: TIM Output clear disable + * @retval None + */ +void TIM_ClearOC4Ref(TIM_TypeDef* TIMx, uint16_t TIM_OCClear) +{ + uint16_t tmpccmr2 = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OCCLEAR_STATE(TIM_OCClear)); + tmpccmr2 = TIMx->CCMR2; + /* Reset the OC4CE Bit */ + tmpccmr2 &= (uint16_t)~((uint16_t)TIM_CCMR2_OC4CE); + /* Enable or Disable the Output Compare Clear Bit */ + tmpccmr2 |= (uint16_t)(TIM_OCClear << 8); + /* Write to TIMx CCMR2 register */ + TIMx->CCMR2 = tmpccmr2; +} + +/** + * @brief Configures the TIMx channel 1 polarity. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC1 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC1P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1P); + tmpccer |= TIM_OCPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 1N polarity. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC1N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC1NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC1NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC1NP); + tmpccer |= TIM_OCNPolarity; + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 2 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC2 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC2P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 2N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC2N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC2NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC2NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC2NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 4); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 3 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC3 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC3P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx Channel 3N polarity. + * @param TIMx: where x can be 1 or 8 to select the TIM peripheral. + * @param TIM_OCNPolarity: specifies the OC3N Polarity + * This parameter can be one of the following values: + * @arg TIM_OCNPolarity_High: Output Compare active high + * @arg TIM_OCNPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC3NPolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCNPolarity) +{ + uint16_t tmpccer = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST1_PERIPH(TIMx)); + assert_param(IS_TIM_OCN_POLARITY(TIM_OCNPolarity)); + + tmpccer = TIMx->CCER; + /* Set or Reset the CC3NP Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC3NP); + tmpccer |= (uint16_t)(TIM_OCNPolarity << 8); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Configures the TIMx channel 4 polarity. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_OCPolarity: specifies the OC4 Polarity + * This parameter can be one of the following values: + * @arg TIM_OCPolarity_High: Output Compare active high + * @arg TIM_OCPolarity_Low: Output Compare active low + * @retval None + */ +void TIM_OC4PolarityConfig(TIM_TypeDef* TIMx, uint16_t TIM_OCPolarity) +{ + uint16_t tmpccer = 0; + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_OC_POLARITY(TIM_OCPolarity)); + tmpccer = TIMx->CCER; + /* Set or Reset the CC4P Bit */ + tmpccer &= (uint16_t)~((uint16_t)TIM_CCER_CC4P); + tmpccer |= (uint16_t)(TIM_OCPolarity << 12); + /* Write to TIMx CCER register */ + TIMx->CCER = tmpccer; +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel x. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_CCx: specifies the TIM Channel CCxE bit new state. + * This parameter can be: TIM_CCx_Enable or TIM_CCx_Disable. + * @retval None + */ +void TIM_CCxCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCx) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCX(TIM_CCx)); + + tmp = CCER_CCE_Set << TIM_Channel; + + /* Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t)~ tmp; + + /* Set or reset the CCxE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCx << TIM_Channel); +} + +/** + * @brief Enables or disables the TIM Capture Compare Channel xN. + * @param TIMx: where x can be 1, 8, 15, 16 or 17 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @param TIM_CCxN: specifies the TIM Channel CCxNE bit new state. + * This parameter can be: TIM_CCxN_Enable or TIM_CCxN_Disable. + * @retval None + */ +void TIM_CCxNCmd(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_CCxN) +{ + uint16_t tmp = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST2_PERIPH(TIMx)); + assert_param(IS_TIM_COMPLEMENTARY_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_CCXN(TIM_CCxN)); + + tmp = CCER_CCNE_Set << TIM_Channel; + + /* Reset the CCxNE Bit */ + TIMx->CCER &= (uint16_t) ~tmp; + + /* Set or reset the CCxNE Bit */ + TIMx->CCER |= (uint16_t)(TIM_CCxN << TIM_Channel); +} + +/** + * @brief Selects the TIM Output Compare Mode. + * @note This function disables the selected channel before changing the Output + * Compare Mode. + * User has to enable this channel using TIM_CCxCmd and TIM_CCxNCmd functions. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_Channel: specifies the TIM Channel + * This parameter can be one of the following values: + * @arg TIM_Channel_1: TIM Channel 1 + * @arg TIM_Channel_2: TIM Channel 2 + * @arg TIM_Channel_3: TIM Channel 3 + * @arg TIM_Channel_4: TIM Channel 4 + * @param TIM_OCMode: specifies the TIM Output Compare Mode. + * This parameter can be one of the following values: + * @arg TIM_OCMode_Timing + * @arg TIM_OCMode_Active + * @arg TIM_OCMode_Toggle + * @arg TIM_OCMode_PWM1 + * @arg TIM_OCMode_PWM2 + * @arg TIM_ForcedAction_Active + * @arg TIM_ForcedAction_InActive + * @retval None + */ +void TIM_SelectOCxM(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode) +{ + uint32_t tmp = 0; + uint16_t tmp1 = 0; + + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CHANNEL(TIM_Channel)); + assert_param(IS_TIM_OCM(TIM_OCMode)); + + tmp = (uint32_t) TIMx; + tmp += CCMR_Offset; + + tmp1 = CCER_CCE_Set << (uint16_t)TIM_Channel; + + /* Disable the Channel: Reset the CCxE Bit */ + TIMx->CCER &= (uint16_t) ~tmp1; + + if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3)) + { + tmp += (TIM_Channel>>1); + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= TIM_OCMode; + } + else + { + tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1; + + /* Reset the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M); + + /* Configure the OCxM bits in the CCMRx register */ + *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8); + } +} + +/** + * @brief Enables or Disables the TIMx Update event. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param NewState: new state of the TIMx UDIS bit + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_UpdateDisableConfig(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the Update Disable Bit */ + TIMx->CR1 |= TIM_CR1_UDIS; + } + else + { + /* Reset the Update Disable Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_UDIS); + } +} + +/** + * @brief Configures the TIMx Update Request Interrupt source. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_UpdateSource: specifies the Update source. + * This parameter can be one of the following values: + * @arg TIM_UpdateSource_Regular: Source of update is the counter overflow/underflow + or the setting of UG bit, or an update generation + through the slave mode controller. + * @arg TIM_UpdateSource_Global: Source of update is counter overflow/underflow. + * @retval None + */ +void TIM_UpdateRequestConfig(TIM_TypeDef* TIMx, uint16_t TIM_UpdateSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_UPDATE_SOURCE(TIM_UpdateSource)); + if (TIM_UpdateSource != TIM_UpdateSource_Global) + { + /* Set the URS Bit */ + TIMx->CR1 |= TIM_CR1_URS; + } + else + { + /* Reset the URS Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_URS); + } +} + +/** + * @brief Enables or disables the TIMx's Hall sensor interface. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param NewState: new state of the TIMx Hall sensor interface. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void TIM_SelectHallSensor(TIM_TypeDef* TIMx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Set the TI1S Bit */ + TIMx->CR2 |= TIM_CR2_TI1S; + } + else + { + /* Reset the TI1S Bit */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_TI1S); + } +} + +/** + * @brief Selects the TIMx's One Pulse Mode. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_OPMode: specifies the OPM Mode to be used. + * This parameter can be one of the following values: + * @arg TIM_OPMode_Single + * @arg TIM_OPMode_Repetitive + * @retval None + */ +void TIM_SelectOnePulseMode(TIM_TypeDef* TIMx, uint16_t TIM_OPMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_OPM_MODE(TIM_OPMode)); + /* Reset the OPM Bit */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_OPM); + /* Configure the OPM Mode */ + TIMx->CR1 |= TIM_OPMode; +} + +/** + * @brief Selects the TIMx Trigger Output Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 6, 7, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_TRGOSource: specifies the Trigger Output source. + * This paramter can be one of the following values: + * + * - For all TIMx + * @arg TIM_TRGOSource_Reset: The UG bit in the TIM_EGR register is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Enable: The Counter Enable CEN is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_Update: The update event is selected as the trigger output (TRGO). + * + * - For all TIMx except TIM6 and TIM7 + * @arg TIM_TRGOSource_OC1: The trigger output sends a positive pulse when the CC1IF flag + * is to be set, as soon as a capture or compare match occurs (TRGO). + * @arg TIM_TRGOSource_OC1Ref: OC1REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC2Ref: OC2REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC3Ref: OC3REF signal is used as the trigger output (TRGO). + * @arg TIM_TRGOSource_OC4Ref: OC4REF signal is used as the trigger output (TRGO). + * + * @retval None + */ +void TIM_SelectOutputTrigger(TIM_TypeDef* TIMx, uint16_t TIM_TRGOSource) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST7_PERIPH(TIMx)); + assert_param(IS_TIM_TRGO_SOURCE(TIM_TRGOSource)); + /* Reset the MMS Bits */ + TIMx->CR2 &= (uint16_t)~((uint16_t)TIM_CR2_MMS); + /* Select the TRGO source */ + TIMx->CR2 |= TIM_TRGOSource; +} + +/** + * @brief Selects the TIMx Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_SlaveMode: specifies the Timer Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_SlaveMode_Reset: Rising edge of the selected trigger signal (TRGI) re-initializes + * the counter and triggers an update of the registers. + * @arg TIM_SlaveMode_Gated: The counter clock is enabled when the trigger signal (TRGI) is high. + * @arg TIM_SlaveMode_Trigger: The counter starts at a rising edge of the trigger TRGI. + * @arg TIM_SlaveMode_External1: Rising edges of the selected trigger (TRGI) clock the counter. + * @retval None + */ +void TIM_SelectSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_SlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_SLAVE_MODE(TIM_SlaveMode)); + /* Reset the SMS Bits */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_SMS); + /* Select the Slave Mode */ + TIMx->SMCR |= TIM_SlaveMode; +} + +/** + * @brief Sets or Resets the TIMx Master/Slave Mode. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_MasterSlaveMode: specifies the Timer Master Slave Mode. + * This parameter can be one of the following values: + * @arg TIM_MasterSlaveMode_Enable: synchronization between the current timer + * and its slaves (through TRGO). + * @arg TIM_MasterSlaveMode_Disable: No action + * @retval None + */ +void TIM_SelectMasterSlaveMode(TIM_TypeDef* TIMx, uint16_t TIM_MasterSlaveMode) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_MSM_STATE(TIM_MasterSlaveMode)); + /* Reset the MSM Bit */ + TIMx->SMCR &= (uint16_t)~((uint16_t)TIM_SMCR_MSM); + + /* Set or Reset the MSM Bit */ + TIMx->SMCR |= TIM_MasterSlaveMode; +} + +/** + * @brief Sets the TIMx Counter Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Counter: specifies the Counter register new value. + * @retval None + */ +void TIM_SetCounter(TIM_TypeDef* TIMx, uint16_t Counter) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Counter Register value */ + TIMx->CNT = Counter; +} + +/** + * @brief Sets the TIMx Autoreload Register value + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param Autoreload: specifies the Autoreload register new value. + * @retval None + */ +void TIM_SetAutoreload(TIM_TypeDef* TIMx, uint16_t Autoreload) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Set the Autoreload Register value */ + TIMx->ARR = Autoreload; +} + +/** + * @brief Sets the TIMx Capture Compare1 Register value + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param Compare1: specifies the Capture Compare1 register new value. + * @retval None + */ +void TIM_SetCompare1(TIM_TypeDef* TIMx, uint16_t Compare1) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Set the Capture Compare1 Register value */ + TIMx->CCR1 = Compare1; +} + +/** + * @brief Sets the TIMx Capture Compare2 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param Compare2: specifies the Capture Compare2 register new value. + * @retval None + */ +void TIM_SetCompare2(TIM_TypeDef* TIMx, uint16_t Compare2) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Set the Capture Compare2 Register value */ + TIMx->CCR2 = Compare2; +} + +/** + * @brief Sets the TIMx Capture Compare3 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare3: specifies the Capture Compare3 register new value. + * @retval None + */ +void TIM_SetCompare3(TIM_TypeDef* TIMx, uint16_t Compare3) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare3 Register value */ + TIMx->CCR3 = Compare3; +} + +/** + * @brief Sets the TIMx Capture Compare4 Register value + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param Compare4: specifies the Capture Compare4 register new value. + * @retval None + */ +void TIM_SetCompare4(TIM_TypeDef* TIMx, uint16_t Compare4) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Set the Capture Compare4 Register value */ + TIMx->CCR4 = Compare4; +} + +/** + * @brief Sets the TIMx Input Capture 1 prescaler. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture1 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC1Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC1PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC1PSC); + /* Set the IC1PSC value */ + TIMx->CCMR1 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 2 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture2 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC2Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC2PSC Bits */ + TIMx->CCMR1 &= (uint16_t)~((uint16_t)TIM_CCMR1_IC2PSC); + /* Set the IC2PSC value */ + TIMx->CCMR1 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Input Capture 3 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture3 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC3Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC3PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC3PSC); + /* Set the IC3PSC value */ + TIMx->CCMR2 |= TIM_ICPSC; +} + +/** + * @brief Sets the TIMx Input Capture 4 prescaler. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPSC: specifies the Input Capture4 prescaler new value. + * This parameter can be one of the following values: + * @arg TIM_ICPSC_DIV1: no prescaler + * @arg TIM_ICPSC_DIV2: capture is done once every 2 events + * @arg TIM_ICPSC_DIV4: capture is done once every 4 events + * @arg TIM_ICPSC_DIV8: capture is done once every 8 events + * @retval None + */ +void TIM_SetIC4Prescaler(TIM_TypeDef* TIMx, uint16_t TIM_ICPSC) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + assert_param(IS_TIM_IC_PRESCALER(TIM_ICPSC)); + /* Reset the IC4PSC Bits */ + TIMx->CCMR2 &= (uint16_t)~((uint16_t)TIM_CCMR2_IC4PSC); + /* Set the IC4PSC value */ + TIMx->CCMR2 |= (uint16_t)(TIM_ICPSC << 8); +} + +/** + * @brief Sets the TIMx Clock Division value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select + * the TIM peripheral. + * @param TIM_CKD: specifies the clock division value. + * This parameter can be one of the following value: + * @arg TIM_CKD_DIV1: TDTS = Tck_tim + * @arg TIM_CKD_DIV2: TDTS = 2*Tck_tim + * @arg TIM_CKD_DIV4: TDTS = 4*Tck_tim + * @retval None + */ +void TIM_SetClockDivision(TIM_TypeDef* TIMx, uint16_t TIM_CKD) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + assert_param(IS_TIM_CKD_DIV(TIM_CKD)); + /* Reset the CKD Bits */ + TIMx->CR1 &= (uint16_t)~((uint16_t)TIM_CR1_CKD); + /* Set the CKD value */ + TIMx->CR1 |= TIM_CKD; +} + +/** + * @brief Gets the TIMx Input Capture 1 value. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @retval Capture Compare 1 Register value. + */ +uint16_t TIM_GetCapture1(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST8_PERIPH(TIMx)); + /* Get the Capture 1 Register value */ + return TIMx->CCR1; +} + +/** + * @brief Gets the TIMx Input Capture 2 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @retval Capture Compare 2 Register value. + */ +uint16_t TIM_GetCapture2(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST6_PERIPH(TIMx)); + /* Get the Capture 2 Register value */ + return TIMx->CCR2; +} + +/** + * @brief Gets the TIMx Input Capture 3 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 3 Register value. + */ +uint16_t TIM_GetCapture3(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 3 Register value */ + return TIMx->CCR3; +} + +/** + * @brief Gets the TIMx Input Capture 4 value. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @retval Capture Compare 4 Register value. + */ +uint16_t TIM_GetCapture4(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_LIST3_PERIPH(TIMx)); + /* Get the Capture 4 Register value */ + return TIMx->CCR4; +} + +/** + * @brief Gets the TIMx Counter value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Counter Register value. + */ +uint16_t TIM_GetCounter(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Counter Register value */ + return TIMx->CNT; +} + +/** + * @brief Gets the TIMx Prescaler value. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @retval Prescaler Register value. + */ +uint16_t TIM_GetPrescaler(TIM_TypeDef* TIMx) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + /* Get the Prescaler Register value */ + return TIMx->PSC; +} + +/** + * @brief Checks whether the specified TIM flag is set or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of TIM_FLAG (SET or RESET). + */ +FlagStatus TIM_GetFlagStatus(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_FLAG(TIM_FLAG)); + + if ((TIMx->SR & TIM_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's pending flags. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_FLAG: specifies the flag bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_FLAG_Update: TIM update Flag + * @arg TIM_FLAG_CC1: TIM Capture Compare 1 Flag + * @arg TIM_FLAG_CC2: TIM Capture Compare 2 Flag + * @arg TIM_FLAG_CC3: TIM Capture Compare 3 Flag + * @arg TIM_FLAG_CC4: TIM Capture Compare 4 Flag + * @arg TIM_FLAG_COM: TIM Commutation Flag + * @arg TIM_FLAG_Trigger: TIM Trigger Flag + * @arg TIM_FLAG_Break: TIM Break Flag + * @arg TIM_FLAG_CC1OF: TIM Capture Compare 1 overcapture Flag + * @arg TIM_FLAG_CC2OF: TIM Capture Compare 2 overcapture Flag + * @arg TIM_FLAG_CC3OF: TIM Capture Compare 3 overcapture Flag + * @arg TIM_FLAG_CC4OF: TIM Capture Compare 4 overcapture Flag + * @note + * - TIM6 and TIM7 can have only one update flag. + * - TIM9, TIM12 and TIM15 can have only TIM_FLAG_Update, TIM_FLAG_CC1, + * TIM_FLAG_CC2 or TIM_FLAG_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_FLAG_Update or TIM_FLAG_CC1. + * - TIM_FLAG_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_FLAG_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearFlag(TIM_TypeDef* TIMx, uint16_t TIM_FLAG) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_CLEAR_FLAG(TIM_FLAG)); + + /* Clear the flags */ + TIMx->SR = (uint16_t)~TIM_FLAG; +} + +/** + * @brief Checks whether the TIM interrupt has occurred or not. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the TIM interrupt source to check. + * This parameter can be one of the following values: + * @arg TIM_IT_Update: TIM update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval The new state of the TIM_IT(SET or RESET). + */ +ITStatus TIM_GetITStatus(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + ITStatus bitstatus = RESET; + uint16_t itstatus = 0x0, itenable = 0x0; + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_GET_IT(TIM_IT)); + + itstatus = TIMx->SR & TIM_IT; + + itenable = TIMx->DIER & TIM_IT; + if ((itstatus != (uint16_t)RESET) && (itenable != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the TIMx's interrupt pending bits. + * @param TIMx: where x can be 1 to 17 to select the TIM peripheral. + * @param TIM_IT: specifies the pending bit to clear. + * This parameter can be any combination of the following values: + * @arg TIM_IT_Update: TIM1 update Interrupt source + * @arg TIM_IT_CC1: TIM Capture Compare 1 Interrupt source + * @arg TIM_IT_CC2: TIM Capture Compare 2 Interrupt source + * @arg TIM_IT_CC3: TIM Capture Compare 3 Interrupt source + * @arg TIM_IT_CC4: TIM Capture Compare 4 Interrupt source + * @arg TIM_IT_COM: TIM Commutation Interrupt source + * @arg TIM_IT_Trigger: TIM Trigger Interrupt source + * @arg TIM_IT_Break: TIM Break Interrupt source + * @note + * - TIM6 and TIM7 can generate only an update interrupt. + * - TIM9, TIM12 and TIM15 can have only TIM_IT_Update, TIM_IT_CC1, + * TIM_IT_CC2 or TIM_IT_Trigger. + * - TIM10, TIM11, TIM13, TIM14, TIM16 and TIM17 can have TIM_IT_Update or TIM_IT_CC1. + * - TIM_IT_Break is used only with TIM1, TIM8 and TIM15. + * - TIM_IT_COM is used only with TIM1, TIM8, TIM15, TIM16 and TIM17. + * @retval None + */ +void TIM_ClearITPendingBit(TIM_TypeDef* TIMx, uint16_t TIM_IT) +{ + /* Check the parameters */ + assert_param(IS_TIM_ALL_PERIPH(TIMx)); + assert_param(IS_TIM_IT(TIM_IT)); + /* Clear the IT pending Bit */ + TIMx->SR = (uint16_t)~TIM_IT; +} + +/** + * @brief Configure the TI1 as Input. + * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 1 is selected to be connected to IC1. + * @arg TIM_ICSelection_IndirectTI: TIM Input 1 is selected to be connected to IC2. + * @arg TIM_ICSelection_TRC: TIM Input 1 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI1_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0; + /* Disable the Channel 1: Reset the CC1E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC1E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC1S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC1F))); + tmpccmr1 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + else + { + /* Select the Polarity and set the CC1E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC1P | TIM_CCER_CC1NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC1E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI2 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5, 8, 9, 12 or 15 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 2 is selected to be connected to IC2. + * @arg TIM_ICSelection_IndirectTI: TIM Input 2 is selected to be connected to IC1. + * @arg TIM_ICSelection_TRC: TIM Input 2 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI2_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr1 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 2: Reset the CC2E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC2E); + tmpccmr1 = TIMx->CCMR1; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 4); + /* Select the Input and set the filter */ + tmpccmr1 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR1_CC2S)) & ((uint16_t)~((uint16_t)TIM_CCMR1_IC2F))); + tmpccmr1 |= (uint16_t)(TIM_ICFilter << 12); + tmpccmr1 |= (uint16_t)(TIM_ICSelection << 8); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC2E); + } + else + { + /* Select the Polarity and set the CC2E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC2P | TIM_CCER_CC2NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC2E); + } + + /* Write to TIMx CCMR1 and CCER registers */ + TIMx->CCMR1 = tmpccmr1 ; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI3 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 3 is selected to be connected to IC3. + * @arg TIM_ICSelection_IndirectTI: TIM Input 3 is selected to be connected to IC4. + * @arg TIM_ICSelection_TRC: TIM Input 3 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI3_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + /* Disable the Channel 3: Reset the CC3E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC3E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 8); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)(((uint16_t)~((uint16_t)TIM_CCMR2_CC3S)) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC3F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection | (uint16_t)(TIM_ICFilter << (uint16_t)4)); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC3E); + } + else + { + /* Select the Polarity and set the CC3E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC3NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC3E); + } + + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @brief Configure the TI4 as Input. + * @param TIMx: where x can be 1, 2, 3, 4, 5 or 8 to select the TIM peripheral. + * @param TIM_ICPolarity : The Input Polarity. + * This parameter can be one of the following values: + * @arg TIM_ICPolarity_Rising + * @arg TIM_ICPolarity_Falling + * @param TIM_ICSelection: specifies the input to be used. + * This parameter can be one of the following values: + * @arg TIM_ICSelection_DirectTI: TIM Input 4 is selected to be connected to IC4. + * @arg TIM_ICSelection_IndirectTI: TIM Input 4 is selected to be connected to IC3. + * @arg TIM_ICSelection_TRC: TIM Input 4 is selected to be connected to TRC. + * @param TIM_ICFilter: Specifies the Input Capture Filter. + * This parameter must be a value between 0x00 and 0x0F. + * @retval None + */ +static void TI4_Config(TIM_TypeDef* TIMx, uint16_t TIM_ICPolarity, uint16_t TIM_ICSelection, + uint16_t TIM_ICFilter) +{ + uint16_t tmpccmr2 = 0, tmpccer = 0, tmp = 0; + + /* Disable the Channel 4: Reset the CC4E Bit */ + TIMx->CCER &= (uint16_t)~((uint16_t)TIM_CCER_CC4E); + tmpccmr2 = TIMx->CCMR2; + tmpccer = TIMx->CCER; + tmp = (uint16_t)(TIM_ICPolarity << 12); + /* Select the Input and set the filter */ + tmpccmr2 &= (uint16_t)((uint16_t)(~(uint16_t)TIM_CCMR2_CC4S) & ((uint16_t)~((uint16_t)TIM_CCMR2_IC4F))); + tmpccmr2 |= (uint16_t)(TIM_ICSelection << 8); + tmpccmr2 |= (uint16_t)(TIM_ICFilter << 12); + + if((TIMx == TIM1) || (TIMx == TIM8) || (TIMx == TIM2) || (TIMx == TIM3) || + (TIMx == TIM4) ||(TIMx == TIM5)) + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC4P)); + tmpccer |= (uint16_t)(tmp | (uint16_t)TIM_CCER_CC4E); + } + else + { + /* Select the Polarity and set the CC4E Bit */ + tmpccer &= (uint16_t)~((uint16_t)(TIM_CCER_CC3P | TIM_CCER_CC4NP)); + tmpccer |= (uint16_t)(TIM_ICPolarity | (uint16_t)TIM_CCER_CC4E); + } + /* Write to TIMx CCMR2 and CCER registers */ + TIMx->CCMR2 = tmpccmr2; + TIMx->CCER = tmpccer; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c new file mode 100755 index 0000000000..a3f16f15ea --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_usart.c @@ -0,0 +1,1058 @@ +/** + ****************************************************************************** + * @file stm32f10x_usart.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the USART firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_usart.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup USART + * @brief USART driver modules + * @{ + */ + +/** @defgroup USART_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Defines + * @{ + */ + +#define CR1_UE_Set ((uint16_t)0x2000) /*!< USART Enable Mask */ +#define CR1_UE_Reset ((uint16_t)0xDFFF) /*!< USART Disable Mask */ + +#define CR1_WAKE_Mask ((uint16_t)0xF7FF) /*!< USART WakeUp Method Mask */ + +#define CR1_RWU_Set ((uint16_t)0x0002) /*!< USART mute mode Enable Mask */ +#define CR1_RWU_Reset ((uint16_t)0xFFFD) /*!< USART mute mode Enable Mask */ +#define CR1_SBK_Set ((uint16_t)0x0001) /*!< USART Break Character send Mask */ +#define CR1_CLEAR_Mask ((uint16_t)0xE9F3) /*!< USART CR1 Mask */ +#define CR2_Address_Mask ((uint16_t)0xFFF0) /*!< USART address Mask */ + +#define CR2_LINEN_Set ((uint16_t)0x4000) /*!< USART LIN Enable Mask */ +#define CR2_LINEN_Reset ((uint16_t)0xBFFF) /*!< USART LIN Disable Mask */ + +#define CR2_LBDL_Mask ((uint16_t)0xFFDF) /*!< USART LIN Break detection Mask */ +#define CR2_STOP_CLEAR_Mask ((uint16_t)0xCFFF) /*!< USART CR2 STOP Bits Mask */ +#define CR2_CLOCK_CLEAR_Mask ((uint16_t)0xF0FF) /*!< USART CR2 Clock Mask */ + +#define CR3_SCEN_Set ((uint16_t)0x0020) /*!< USART SC Enable Mask */ +#define CR3_SCEN_Reset ((uint16_t)0xFFDF) /*!< USART SC Disable Mask */ + +#define CR3_NACK_Set ((uint16_t)0x0010) /*!< USART SC NACK Enable Mask */ +#define CR3_NACK_Reset ((uint16_t)0xFFEF) /*!< USART SC NACK Disable Mask */ + +#define CR3_HDSEL_Set ((uint16_t)0x0008) /*!< USART Half-Duplex Enable Mask */ +#define CR3_HDSEL_Reset ((uint16_t)0xFFF7) /*!< USART Half-Duplex Disable Mask */ + +#define CR3_IRLP_Mask ((uint16_t)0xFFFB) /*!< USART IrDA LowPower mode Mask */ +#define CR3_CLEAR_Mask ((uint16_t)0xFCFF) /*!< USART CR3 Mask */ + +#define CR3_IREN_Set ((uint16_t)0x0002) /*!< USART IrDA Enable Mask */ +#define CR3_IREN_Reset ((uint16_t)0xFFFD) /*!< USART IrDA Disable Mask */ +#define GTPR_LSB_Mask ((uint16_t)0x00FF) /*!< Guard Time Register LSB Mask */ +#define GTPR_MSB_Mask ((uint16_t)0xFF00) /*!< Guard Time Register MSB Mask */ +#define IT_Mask ((uint16_t)0x001F) /*!< USART Interrupt Mask */ + +/* USART OverSampling-8 Mask */ +#define CR1_OVER8_Set ((u16)0x8000) /* USART OVER8 mode Enable Mask */ +#define CR1_OVER8_Reset ((u16)0x7FFF) /* USART OVER8 mode Disable Mask */ + +/* USART One Bit Sampling Mask */ +#define CR3_ONEBITE_Set ((u16)0x0800) /* USART ONEBITE mode Enable Mask */ +#define CR3_ONEBITE_Reset ((u16)0xF7FF) /* USART ONEBITE mode Disable Mask */ + +/** + * @} + */ + +/** @defgroup USART_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup USART_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the USARTx peripheral registers to their default reset values. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_DeInit(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + if (USARTx == USART1) + { + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, ENABLE); + RCC_APB2PeriphResetCmd(RCC_APB2Periph_USART1, DISABLE); + } + else if (USARTx == USART2) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART2, DISABLE); + } + else if (USARTx == USART3) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_USART3, DISABLE); + } + else if (USARTx == UART4) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART4, DISABLE); + } + else + { + if (USARTx == UART5) + { + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_UART5, DISABLE); + } + } +} + +/** + * @brief Initializes the USARTx peripheral according to the specified + * parameters in the USART_InitStruct . + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * that contains the configuration information for the specified USART + * peripheral. + * @retval None + */ +void USART_Init(USART_TypeDef* USARTx, USART_InitTypeDef* USART_InitStruct) +{ + uint32_t tmpreg = 0x00, apbclock = 0x00; + uint32_t integerdivider = 0x00; + uint32_t fractionaldivider = 0x00; + uint32_t usartxbase = 0; + RCC_ClocksTypeDef RCC_ClocksStatus; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_BAUDRATE(USART_InitStruct->USART_BaudRate)); + assert_param(IS_USART_WORD_LENGTH(USART_InitStruct->USART_WordLength)); + assert_param(IS_USART_STOPBITS(USART_InitStruct->USART_StopBits)); + assert_param(IS_USART_PARITY(USART_InitStruct->USART_Parity)); + assert_param(IS_USART_MODE(USART_InitStruct->USART_Mode)); + assert_param(IS_USART_HARDWARE_FLOW_CONTROL(USART_InitStruct->USART_HardwareFlowControl)); + /* The hardware flow control is available only for USART1, USART2 and USART3 */ + if (USART_InitStruct->USART_HardwareFlowControl != USART_HardwareFlowControl_None) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear STOP[13:12] bits */ + tmpreg &= CR2_STOP_CLEAR_Mask; + /* Configure the USART Stop Bits, Clock, CPOL, CPHA and LastBit ------------*/ + /* Set STOP[13:12] bits according to USART_StopBits value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_StopBits; + + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; + +/*---------------------------- USART CR1 Configuration -----------------------*/ + tmpreg = USARTx->CR1; + /* Clear M, PCE, PS, TE and RE bits */ + tmpreg &= CR1_CLEAR_Mask; + /* Configure the USART Word Length, Parity and mode ----------------------- */ + /* Set the M bits according to USART_WordLength value */ + /* Set PCE and PS bits according to USART_Parity value */ + /* Set TE and RE bits according to USART_Mode value */ + tmpreg |= (uint32_t)USART_InitStruct->USART_WordLength | USART_InitStruct->USART_Parity | + USART_InitStruct->USART_Mode; + /* Write to USART CR1 */ + USARTx->CR1 = (uint16_t)tmpreg; + +/*---------------------------- USART CR3 Configuration -----------------------*/ + tmpreg = USARTx->CR3; + /* Clear CTSE and RTSE bits */ + tmpreg &= CR3_CLEAR_Mask; + /* Configure the USART HFC -------------------------------------------------*/ + /* Set CTSE and RTSE bits according to USART_HardwareFlowControl value */ + tmpreg |= USART_InitStruct->USART_HardwareFlowControl; + /* Write to USART CR3 */ + USARTx->CR3 = (uint16_t)tmpreg; + +/*---------------------------- USART BRR Configuration -----------------------*/ + /* Configure the USART Baud Rate -------------------------------------------*/ + RCC_GetClocksFreq(&RCC_ClocksStatus); + if (usartxbase == USART1_BASE) + { + apbclock = RCC_ClocksStatus.PCLK2_Frequency; + } + else + { + apbclock = RCC_ClocksStatus.PCLK1_Frequency; + } + + /* Determine the integer part */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + /* Integer part computing in case Oversampling mode is 8 Samples */ + integerdivider = ((25 * apbclock) / (2 * (USART_InitStruct->USART_BaudRate))); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + /* Integer part computing in case Oversampling mode is 16 Samples */ + integerdivider = ((25 * apbclock) / (4 * (USART_InitStruct->USART_BaudRate))); + } + tmpreg = (integerdivider / 100) << 4; + + /* Determine the fractional part */ + fractionaldivider = integerdivider - (100 * (tmpreg >> 4)); + + /* Implement the fractional part in the register */ + if ((USARTx->CR1 & CR1_OVER8_Set) != 0) + { + tmpreg |= ((((fractionaldivider * 8) + 50) / 100)) & ((uint8_t)0x07); + } + else /* if ((USARTx->CR1 & CR1_OVER8_Set) == 0) */ + { + tmpreg |= ((((fractionaldivider * 16) + 50) / 100)) & ((uint8_t)0x0F); + } + + /* Write to USART BRR */ + USARTx->BRR = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_InitStruct member with its default value. + * @param USART_InitStruct: pointer to a USART_InitTypeDef structure + * which will be initialized. + * @retval None + */ +void USART_StructInit(USART_InitTypeDef* USART_InitStruct) +{ + /* USART_InitStruct members default value */ + USART_InitStruct->USART_BaudRate = 9600; + USART_InitStruct->USART_WordLength = USART_WordLength_8b; + USART_InitStruct->USART_StopBits = USART_StopBits_1; + USART_InitStruct->USART_Parity = USART_Parity_No ; + USART_InitStruct->USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_InitStruct->USART_HardwareFlowControl = USART_HardwareFlowControl_None; +} + +/** + * @brief Initializes the USARTx peripheral Clock according to the + * specified parameters in the USART_ClockInitStruct . + * @param USARTx: where x can be 1, 2, 3 to select the USART peripheral. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure that contains the configuration information for the specified + * USART peripheral. + * @note The Smart Card and Synchronous modes are not available for UART4 and UART5. + * @retval None + */ +void USART_ClockInit(USART_TypeDef* USARTx, USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + uint32_t tmpreg = 0x00; + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_USART_CLOCK(USART_ClockInitStruct->USART_Clock)); + assert_param(IS_USART_CPOL(USART_ClockInitStruct->USART_CPOL)); + assert_param(IS_USART_CPHA(USART_ClockInitStruct->USART_CPHA)); + assert_param(IS_USART_LASTBIT(USART_ClockInitStruct->USART_LastBit)); + +/*---------------------------- USART CR2 Configuration -----------------------*/ + tmpreg = USARTx->CR2; + /* Clear CLKEN, CPOL, CPHA and LBCL bits */ + tmpreg &= CR2_CLOCK_CLEAR_Mask; + /* Configure the USART Clock, CPOL, CPHA and LastBit ------------*/ + /* Set CLKEN bit according to USART_Clock value */ + /* Set CPOL bit according to USART_CPOL value */ + /* Set CPHA bit according to USART_CPHA value */ + /* Set LBCL bit according to USART_LastBit value */ + tmpreg |= (uint32_t)USART_ClockInitStruct->USART_Clock | USART_ClockInitStruct->USART_CPOL | + USART_ClockInitStruct->USART_CPHA | USART_ClockInitStruct->USART_LastBit; + /* Write to USART CR2 */ + USARTx->CR2 = (uint16_t)tmpreg; +} + +/** + * @brief Fills each USART_ClockInitStruct member with its default value. + * @param USART_ClockInitStruct: pointer to a USART_ClockInitTypeDef + * structure which will be initialized. + * @retval None + */ +void USART_ClockStructInit(USART_ClockInitTypeDef* USART_ClockInitStruct) +{ + /* USART_ClockInitStruct members default value */ + USART_ClockInitStruct->USART_Clock = USART_Clock_Disable; + USART_ClockInitStruct->USART_CPOL = USART_CPOL_Low; + USART_ClockInitStruct->USART_CPHA = USART_CPHA_1Edge; + USART_ClockInitStruct->USART_LastBit = USART_LastBit_Disable; +} + +/** + * @brief Enables or disables the specified USART peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USARTx peripheral. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the selected USART by setting the UE bit in the CR1 register */ + USARTx->CR1 |= CR1_UE_Set; + } + else + { + /* Disable the selected USART by clearing the UE bit in the CR1 register */ + USARTx->CR1 &= CR1_UE_Reset; + } +} + +/** + * @brief Enables or disables the specified USART interrupts. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt sources to be enabled or disabled. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Transmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) + * @param NewState: new state of the specified USARTx interrupts. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ITConfig(USART_TypeDef* USARTx, uint16_t USART_IT, FunctionalState NewState) +{ + uint32_t usartreg = 0x00, itpos = 0x00, itmask = 0x00; + uint32_t usartxbase = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CONFIG_IT(USART_IT)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + usartxbase = (uint32_t)USARTx; + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + + /* Get the interrupt position */ + itpos = USART_IT & IT_Mask; + itmask = (((uint32_t)0x01) << itpos); + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + usartxbase += 0x0C; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + usartxbase += 0x10; + } + else /* The IT is in CR3 register */ + { + usartxbase += 0x14; + } + if (NewState != DISABLE) + { + *(__IO uint32_t*)usartxbase |= itmask; + } + else + { + *(__IO uint32_t*)usartxbase &= ~itmask; + } +} + +/** + * @brief Enables or disables the USART’s DMA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_DMAReq: specifies the DMA request. + * This parameter can be any combination of the following values: + * @arg USART_DMAReq_Tx: USART DMA transmit request + * @arg USART_DMAReq_Rx: USART DMA receive request + * @param NewState: new state of the DMA Request sources. + * This parameter can be: ENABLE or DISABLE. + * @note The DMA mode is not available for UART5 except in the STM32 + * High density value line devices(STM32F10X_HD_VL). + * @retval None + */ +void USART_DMACmd(USART_TypeDef* USARTx, uint16_t USART_DMAReq, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DMAREQ(USART_DMAReq)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the DMA transfer for selected requests by setting the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 |= USART_DMAReq; + } + else + { + /* Disable the DMA transfer for selected requests by clearing the DMAT and/or + DMAR bits in the USART CR3 register */ + USARTx->CR3 &= (uint16_t)~USART_DMAReq; + } +} + +/** + * @brief Sets the address of the USART node. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Address: Indicates the address of the USART node. + * @retval None + */ +void USART_SetAddress(USART_TypeDef* USARTx, uint8_t USART_Address) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_ADDRESS(USART_Address)); + + /* Clear the USART address */ + USARTx->CR2 &= CR2_Address_Mask; + /* Set the USART address node */ + USARTx->CR2 |= USART_Address; +} + +/** + * @brief Selects the USART WakeUp method. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_WakeUp: specifies the USART wakeup method. + * This parameter can be one of the following values: + * @arg USART_WakeUp_IdleLine: WakeUp by an idle line detection + * @arg USART_WakeUp_AddressMark: WakeUp by an address mark + * @retval None + */ +void USART_WakeUpConfig(USART_TypeDef* USARTx, uint16_t USART_WakeUp) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_WAKEUP(USART_WakeUp)); + + USARTx->CR1 &= CR1_WAKE_Mask; + USARTx->CR1 |= USART_WakeUp; +} + +/** + * @brief Determines if the USART is in mute mode or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART mute mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_ReceiverWakeUpCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the USART mute mode by setting the RWU bit in the CR1 register */ + USARTx->CR1 |= CR1_RWU_Set; + } + else + { + /* Disable the USART mute mode by clearing the RWU bit in the CR1 register */ + USARTx->CR1 &= CR1_RWU_Reset; + } +} + +/** + * @brief Sets the USART LIN Break detection length. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_LINBreakDetectLength: specifies the LIN break detection length. + * This parameter can be one of the following values: + * @arg USART_LINBreakDetectLength_10b: 10-bit break detection + * @arg USART_LINBreakDetectLength_11b: 11-bit break detection + * @retval None + */ +void USART_LINBreakDetectLengthConfig(USART_TypeDef* USARTx, uint16_t USART_LINBreakDetectLength) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_LIN_BREAK_DETECT_LENGTH(USART_LINBreakDetectLength)); + + USARTx->CR2 &= CR2_LBDL_Mask; + USARTx->CR2 |= USART_LINBreakDetectLength; +} + +/** + * @brief Enables or disables the USART’s LIN mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART LIN mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_LINCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the LIN mode by setting the LINEN bit in the CR2 register */ + USARTx->CR2 |= CR2_LINEN_Set; + } + else + { + /* Disable the LIN mode by clearing the LINEN bit in the CR2 register */ + USARTx->CR2 &= CR2_LINEN_Reset; + } +} + +/** + * @brief Transmits single data through the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param Data: the data to transmit. + * @retval None + */ +void USART_SendData(USART_TypeDef* USARTx, uint16_t Data) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_DATA(Data)); + + /* Transmit Data */ + USARTx->DR = (Data & (uint16_t)0x01FF); +} + +/** + * @brief Returns the most recent received data by the USARTx peripheral. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval The received data. + */ +uint16_t USART_ReceiveData(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Receive Data */ + return (uint16_t)(USARTx->DR & (uint16_t)0x01FF); +} + +/** + * @brief Transmits break characters. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @retval None + */ +void USART_SendBreak(USART_TypeDef* USARTx) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Send break characters */ + USARTx->CR1 |= CR1_SBK_Set; +} + +/** + * @brief Sets the specified USART guard time. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param USART_GuardTime: specifies the guard time. + * @note The guard time bits are not available for UART4 and UART5. + * @retval None + */ +void USART_SetGuardTime(USART_TypeDef* USARTx, uint8_t USART_GuardTime) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + + /* Clear the USART Guard time */ + USARTx->GTPR &= GTPR_LSB_Mask; + /* Set the USART guard time */ + USARTx->GTPR |= (uint16_t)((uint16_t)USART_GuardTime << 0x08); +} + +/** + * @brief Sets the system clock prescaler. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_Prescaler: specifies the prescaler clock. + * @note The function is used for IrDA mode with UART4 and UART5. + * @retval None + */ +void USART_SetPrescaler(USART_TypeDef* USARTx, uint8_t USART_Prescaler) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + + /* Clear the USART prescaler */ + USARTx->GTPR &= GTPR_MSB_Mask; + /* Set the USART prescaler */ + USARTx->GTPR |= USART_Prescaler; +} + +/** + * @brief Enables or disables the USART’s Smart Card mode. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the Smart Card mode. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the SC mode by setting the SCEN bit in the CR3 register */ + USARTx->CR3 |= CR3_SCEN_Set; + } + else + { + /* Disable the SC mode by clearing the SCEN bit in the CR3 register */ + USARTx->CR3 &= CR3_SCEN_Reset; + } +} + +/** + * @brief Enables or disables NACK transmission. + * @param USARTx: where x can be 1, 2 or 3 to select the USART peripheral. + * @param NewState: new state of the NACK transmission. + * This parameter can be: ENABLE or DISABLE. + * @note The Smart Card mode is not available for UART4 and UART5. + * @retval None + */ +void USART_SmartCardNACKCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_123_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + { + /* Enable the NACK transmission by setting the NACK bit in the CR3 register */ + USARTx->CR3 |= CR3_NACK_Set; + } + else + { + /* Disable the NACK transmission by clearing the NACK bit in the CR3 register */ + USARTx->CR3 &= CR3_NACK_Reset; + } +} + +/** + * @brief Enables or disables the USART’s Half Duplex communication. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART Communication. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_HalfDuplexCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the Half-Duplex mode by setting the HDSEL bit in the CR3 register */ + USARTx->CR3 |= CR3_HDSEL_Set; + } + else + { + /* Disable the Half-Duplex mode by clearing the HDSEL bit in the CR3 register */ + USARTx->CR3 &= CR3_HDSEL_Reset; + } +} + + +/** + * @brief Enables or disables the USART's 8x oversampling mode. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @note + * This function has to be called before calling USART_Init() + * function in order to have correct baudrate Divider value. + * @retval None + */ +void USART_OverSampling8Cmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the 8x Oversampling mode by setting the OVER8 bit in the CR1 register */ + USARTx->CR1 |= CR1_OVER8_Set; + } + else + { + /* Disable the 8x Oversampling mode by clearing the OVER8 bit in the CR1 register */ + USARTx->CR1 &= CR1_OVER8_Reset; + } +} + +/** + * @brief Enables or disables the USART's one bit sampling method. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the USART one bit sampling method. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_OneBitMethodCmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the one bit method by setting the ONEBITE bit in the CR3 register */ + USARTx->CR3 |= CR3_ONEBITE_Set; + } + else + { + /* Disable tthe one bit method by clearing the ONEBITE bit in the CR3 register */ + USARTx->CR3 &= CR3_ONEBITE_Reset; + } +} + +/** + * @brief Configures the USART's IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IrDAMode: specifies the IrDA mode. + * This parameter can be one of the following values: + * @arg USART_IrDAMode_LowPower + * @arg USART_IrDAMode_Normal + * @retval None + */ +void USART_IrDAConfig(USART_TypeDef* USARTx, uint16_t USART_IrDAMode) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_IRDA_MODE(USART_IrDAMode)); + + USARTx->CR3 &= CR3_IRLP_Mask; + USARTx->CR3 |= USART_IrDAMode; +} + +/** + * @brief Enables or disables the USART's IrDA interface. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param NewState: new state of the IrDA mode. + * This parameter can be: ENABLE or DISABLE. + * @retval None + */ +void USART_IrDACmd(USART_TypeDef* USARTx, FunctionalState NewState) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + { + /* Enable the IrDA mode by setting the IREN bit in the CR3 register */ + USARTx->CR3 |= CR3_IREN_Set; + } + else + { + /* Disable the IrDA mode by clearing the IREN bit in the CR3 register */ + USARTx->CR3 &= CR3_IREN_Reset; + } +} + +/** + * @brief Checks whether the specified USART flag is set or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to check. + * This parameter can be one of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) + * @arg USART_FLAG_LBD: LIN Break detection flag + * @arg USART_FLAG_TXE: Transmit data register empty flag + * @arg USART_FLAG_TC: Transmission Complete flag + * @arg USART_FLAG_RXNE: Receive data register not empty flag + * @arg USART_FLAG_IDLE: Idle Line detection flag + * @arg USART_FLAG_ORE: OverRun Error flag + * @arg USART_FLAG_NE: Noise Error flag + * @arg USART_FLAG_FE: Framing Error flag + * @arg USART_FLAG_PE: Parity Error flag + * @retval The new state of USART_FLAG (SET or RESET). + */ +FlagStatus USART_GetFlagStatus(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + FlagStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if (USART_FLAG == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + if ((USARTx->SR & USART_FLAG) != (uint16_t)RESET) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + return bitstatus; +} + +/** + * @brief Clears the USARTx's pending flags. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_FLAG: specifies the flag to clear. + * This parameter can be any combination of the following values: + * @arg USART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). + * @arg USART_FLAG_LBD: LIN Break detection flag. + * @arg USART_FLAG_TC: Transmission Complete flag. + * @arg USART_FLAG_RXNE: Receive data register not empty flag. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) flags are cleared by software + * sequence: a read operation to USART_SR register (USART_GetFlagStatus()) + * followed by a read operation to USART_DR register (USART_ReceiveData()). + * - RXNE flag can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC flag can be also cleared by software sequence: a read operation to + * USART_SR register (USART_GetFlagStatus()) followed by a write operation + * to USART_DR register (USART_SendData()). + * - TXE flag is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearFlag(USART_TypeDef* USARTx, uint16_t USART_FLAG) +{ + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_FLAG(USART_FLAG)); + /* The CTS flag is not available for UART4 and UART5 */ + if ((USART_FLAG & USART_FLAG_CTS) == USART_FLAG_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + USARTx->SR = (uint16_t)~USART_FLAG; +} + +/** + * @brief Checks whether the specified USART interrupt has occurred or not. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the USART interrupt source to check. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TXE: Tansmit Data Register empty interrupt + * @arg USART_IT_TC: Transmission complete interrupt + * @arg USART_IT_RXNE: Receive Data register not empty interrupt + * @arg USART_IT_IDLE: Idle line detection interrupt + * @arg USART_IT_ORE: OverRun Error interrupt + * @arg USART_IT_NE: Noise Error interrupt + * @arg USART_IT_FE: Framing Error interrupt + * @arg USART_IT_PE: Parity Error interrupt + * @retval The new state of USART_IT (SET or RESET). + */ +ITStatus USART_GetITStatus(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint32_t bitpos = 0x00, itmask = 0x00, usartreg = 0x00; + ITStatus bitstatus = RESET; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_GET_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + /* Get the USART register index */ + usartreg = (((uint8_t)USART_IT) >> 0x05); + /* Get the interrupt position */ + itmask = USART_IT & IT_Mask; + itmask = (uint32_t)0x01 << itmask; + + if (usartreg == 0x01) /* The IT is in CR1 register */ + { + itmask &= USARTx->CR1; + } + else if (usartreg == 0x02) /* The IT is in CR2 register */ + { + itmask &= USARTx->CR2; + } + else /* The IT is in CR3 register */ + { + itmask &= USARTx->CR3; + } + + bitpos = USART_IT >> 0x08; + bitpos = (uint32_t)0x01 << bitpos; + bitpos &= USARTx->SR; + if ((itmask != (uint16_t)RESET)&&(bitpos != (uint16_t)RESET)) + { + bitstatus = SET; + } + else + { + bitstatus = RESET; + } + + return bitstatus; +} + +/** + * @brief Clears the USARTx's interrupt pending bits. + * @param USARTx: Select the USART or the UART peripheral. + * This parameter can be one of the following values: + * USART1, USART2, USART3, UART4 or UART5. + * @param USART_IT: specifies the interrupt pending bit to clear. + * This parameter can be one of the following values: + * @arg USART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) + * @arg USART_IT_LBD: LIN Break detection interrupt + * @arg USART_IT_TC: Transmission complete interrupt. + * @arg USART_IT_RXNE: Receive Data register not empty interrupt. + * + * @note + * - PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun + * error) and IDLE (Idle line detected) pending bits are cleared by + * software sequence: a read operation to USART_SR register + * (USART_GetITStatus()) followed by a read operation to USART_DR register + * (USART_ReceiveData()). + * - RXNE pending bit can be also cleared by a read to the USART_DR register + * (USART_ReceiveData()). + * - TC pending bit can be also cleared by software sequence: a read + * operation to USART_SR register (USART_GetITStatus()) followed by a write + * operation to USART_DR register (USART_SendData()). + * - TXE pending bit is cleared only by a write to the USART_DR register + * (USART_SendData()). + * @retval None + */ +void USART_ClearITPendingBit(USART_TypeDef* USARTx, uint16_t USART_IT) +{ + uint16_t bitpos = 0x00, itmask = 0x00; + /* Check the parameters */ + assert_param(IS_USART_ALL_PERIPH(USARTx)); + assert_param(IS_USART_CLEAR_IT(USART_IT)); + /* The CTS interrupt is not available for UART4 and UART5 */ + if (USART_IT == USART_IT_CTS) + { + assert_param(IS_USART_123_PERIPH(USARTx)); + } + + bitpos = USART_IT >> 0x08; + itmask = ((uint16_t)0x01 << (uint16_t)bitpos); + USARTx->SR = (uint16_t)~itmask; +} +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c new file mode 100755 index 0000000000..77a7ce517d --- /dev/null +++ b/src/baseflight/lib/STM32F10x_StdPeriph_Driver/src/stm32f10x_wwdg.c @@ -0,0 +1,224 @@ +/** + ****************************************************************************** + * @file stm32f10x_wwdg.c + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief This file provides all the WWDG firmware functions. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_wwdg.h" +#include "stm32f10x_rcc.h" + +/** @addtogroup STM32F10x_StdPeriph_Driver + * @{ + */ + +/** @defgroup WWDG + * @brief WWDG driver modules + * @{ + */ + +/** @defgroup WWDG_Private_TypesDefinitions + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Defines + * @{ + */ + +/* ----------- WWDG registers bit address in the alias region ----------- */ +#define WWDG_OFFSET (WWDG_BASE - PERIPH_BASE) + +/* Alias word address of EWI bit */ +#define CFR_OFFSET (WWDG_OFFSET + 0x04) +#define EWI_BitNumber 0x09 +#define CFR_EWI_BB (PERIPH_BB_BASE + (CFR_OFFSET * 32) + (EWI_BitNumber * 4)) + +/* --------------------- WWDG registers bit mask ------------------------ */ + +/* CR register bit mask */ +#define CR_WDGA_Set ((uint32_t)0x00000080) + +/* CFR register bit mask */ +#define CFR_WDGTB_Mask ((uint32_t)0xFFFFFE7F) +#define CFR_W_Mask ((uint32_t)0xFFFFFF80) +#define BIT_Mask ((uint8_t)0x7F) + +/** + * @} + */ + +/** @defgroup WWDG_Private_Macros + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Variables + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_FunctionPrototypes + * @{ + */ + +/** + * @} + */ + +/** @defgroup WWDG_Private_Functions + * @{ + */ + +/** + * @brief Deinitializes the WWDG peripheral registers to their default reset values. + * @param None + * @retval None + */ +void WWDG_DeInit(void) +{ + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, ENABLE); + RCC_APB1PeriphResetCmd(RCC_APB1Periph_WWDG, DISABLE); +} + +/** + * @brief Sets the WWDG Prescaler. + * @param WWDG_Prescaler: specifies the WWDG Prescaler. + * This parameter can be one of the following values: + * @arg WWDG_Prescaler_1: WWDG counter clock = (PCLK1/4096)/1 + * @arg WWDG_Prescaler_2: WWDG counter clock = (PCLK1/4096)/2 + * @arg WWDG_Prescaler_4: WWDG counter clock = (PCLK1/4096)/4 + * @arg WWDG_Prescaler_8: WWDG counter clock = (PCLK1/4096)/8 + * @retval None + */ +void WWDG_SetPrescaler(uint32_t WWDG_Prescaler) +{ + uint32_t tmpreg = 0; + /* Check the parameters */ + assert_param(IS_WWDG_PRESCALER(WWDG_Prescaler)); + /* Clear WDGTB[1:0] bits */ + tmpreg = WWDG->CFR & CFR_WDGTB_Mask; + /* Set WDGTB[1:0] bits according to WWDG_Prescaler value */ + tmpreg |= WWDG_Prescaler; + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Sets the WWDG window value. + * @param WindowValue: specifies the window value to be compared to the downcounter. + * This parameter value must be lower than 0x80. + * @retval None + */ +void WWDG_SetWindowValue(uint8_t WindowValue) +{ + __IO uint32_t tmpreg = 0; + + /* Check the parameters */ + assert_param(IS_WWDG_WINDOW_VALUE(WindowValue)); + /* Clear W[6:0] bits */ + + tmpreg = WWDG->CFR & CFR_W_Mask; + + /* Set W[6:0] bits according to WindowValue value */ + tmpreg |= WindowValue & (uint32_t) BIT_Mask; + + /* Store the new value */ + WWDG->CFR = tmpreg; +} + +/** + * @brief Enables the WWDG Early Wakeup interrupt(EWI). + * @param None + * @retval None + */ +void WWDG_EnableIT(void) +{ + *(__IO uint32_t *) CFR_EWI_BB = (uint32_t)ENABLE; +} + +/** + * @brief Sets the WWDG counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_SetCounter(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + /* Write to T[6:0] bits to configure the counter value, no need to do + a read-modify-write; writing a 0 to WDGA bit does nothing */ + WWDG->CR = Counter & BIT_Mask; +} + +/** + * @brief Enables WWDG and load the counter value. + * @param Counter: specifies the watchdog counter value. + * This parameter must be a number between 0x40 and 0x7F. + * @retval None + */ +void WWDG_Enable(uint8_t Counter) +{ + /* Check the parameters */ + assert_param(IS_WWDG_COUNTER(Counter)); + WWDG->CR = CR_WDGA_Set | Counter; +} + +/** + * @brief Checks whether the Early Wakeup interrupt flag is set or not. + * @param None + * @retval The new state of the Early Wakeup interrupt flag (SET or RESET) + */ +FlagStatus WWDG_GetFlagStatus(void) +{ + return (FlagStatus)(WWDG->SR); +} + +/** + * @brief Clears Early Wakeup interrupt flag. + * @param None + * @retval None + */ +void WWDG_ClearFlag(void) +{ + WWDG->SR = (uint32_t)RESET; +} + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/baseflight/obj/baseflight.hex b/src/baseflight/obj/baseflight.hex new file mode 100644 index 0000000000..7503bc78ad --- /dev/null +++ b/src/baseflight/obj/baseflight.hex @@ -0,0 +1,3153 @@ +:020000040800F2 +:10000000481E00204189000881890008CF1F000890 +:100010008589000887890008898900080000000098 +:100020000000000000000000000000008B890008B4 +:100030008D890008000000008F890008256B0008EA +:100040009389000893890008938900089389000820 +:100050009389000893890008938900086B7400084D +:100060009389000893890008938900089389000800 +:1000700093890008938900083F6D00089389000860 +:1000800093890008938900089389000893890008E0 +:100090009389000893890008938900086D7400080B +:1000A0009389000893890008938900085367000822 +:1000B0003F680008476800084D680008EF620008C4 +:1000C000CD600008F3620008F1620008938900081F +:1000D0009389000893890008F56F00089389000848 +:1000E000DD5B00089389000893890008DFF80CD0D5 +:1000F00009F0CAFA00480047131E0008481E0020F5 +:1001000070B51446B0FBF4F60546A04203D3304662 +:10011000FFF7F6FF014604FB1650F8A2105C0870CA +:10012000481C70BD70B50C46911E232900D30A22CD +:100130000025002804DA2D212170611C404200E0D6 +:100140002146FFF7DDFF0570204670BD2DE9F05F09 +:10015000044600E0641C20782028FBD00928F9D050 +:10016000DFF8C0A3C1B24FF000092D2902D02B281F +:1001700004D004E0DFF8B0A34FF00009641C0026AF +:100180003746DFF8A8B310E009F062F80546884664 +:1001900000225B463046394608F06BFF2A4643464C +:1001A00008F0C0FE06460F46641C20783038092847 +:1001B000EAD920782E281CD10025DFF8708313E0BF +:1001C00009F046F82A46434608F0C5FF32463B464A +:1001D00008F0A8FE06460F4600225B462846414628 +:1001E00008F047FF0546884614F8010F3038092803 +:1001F000E6D922780020CB49652A01D0452A43D18F +:1002000014F8012F4FF000082D2A02D02B2A02D01B +:1002100002E04FF00108641C00256FF02F0305E099 +:1002200005EB850503EB45051544641C2278A2F116 +:10023000300CBCF1090FF3D94FF49A72954205D9ED +:100240001546BB4ABB4B08F014FF323D322DF8D2A5 +:10025000B94C082D0BD30022234608F00AFF083DB5 +:10026000F7E70022234608F004FF6D1E00E05C461D +:10027000002DF6D1B8F1000F06D002460B463046ED +:10028000394608F068FF03E032463B4608F0F1FECD +:100290004A46534608F0EDFEBDE8F05F09F048B865 +:1002A000F0B587B000260D46A54900960196A3A794 +:1002B0000296B0F5000F02DB08F05AFD01E008F0ED +:1002C000A9FDA04908F0ACFD08F0D3FF041E00DC36 +:1002D00060420A2203A9FFF725FF002C01DB202042 +:1002E00000E02D208DF8000003A808F013FD302455 +:1002F00001280AD003A808F00DFD02280CD003A89D +:1003000008F008FD03280CD00DE08DF801408DF8B1 +:1003100002408DF8034006E08DF801408DF8024060 +:1003200001E08DF8014003A9684608F0BAFC684670 +:1003300008F0F0FCC01EC4B222466946284608F008 +:10034000D4FC2E553946284608F0ABFC0DEB0401D1 +:10035000284608F0A6FC07B02846F0BD70B5054653 +:100360000C46086808F0D6FC024621682868BDE8FB +:10037000704008F0D7BC2DE9F041002488B0074652 +:10038000264608F0C7FC704D10F0FF0F4FD0042236 +:100390006EA1384608F0C6FC00287DD0384608F02B +:1003A000DAFC461E0C2E78DA2021384608F0A9FC2B +:1003B000070008D0781C0746FFF7C8FE05EB0611BA +:1003C0000124C1F804012021384608F09AFC0700F6 +:1003D00008D0471C3846FFF7B9FE05EB0611641C30 +:1003E000C1F808012021384608F08BFC070008D02E +:1003F000471C3846FFF7AAFE05EB0611641CC1F83E +:100400000C012021384608F07CFC38B1401CFFF775 +:100410009DFE05EB0611641CC1F81001042C6BD085 +:100420004CA000BF06F058FD08B0BDE8F08158A010 +:1004300006F052FD00240DF1100800BF05EB041773 +:10044000D7F8040110F0FF4F2FD0002148F82410F6 +:10045000761C611C59A008F0BFFB07F5827769463E +:100460003868FFF71DFF014656A008F0B5FB694646 +:100470007868FFF715FF014652A008F0ADFB69460A +:10048000B868FFF70DFF01464EA008F0A5FB6946CE +:10049000F868FFF705FF01E0B0E0D6E001464AA0AA +:1004A00008F09AFB641C0C2CC8DB002414E000BF8D +:1004B00005EB041707F584770498396808F058FCB1 +:1004C00004907968059808F053FC0590B96806987F +:1004D00008F04EFC641C0690B442E9DB3CA006F038 +:1004E000FBFC3F4E0024454655F8240020F0004018 +:1004F000B04279DD3BA078E0A2E075E030313233E4 +:100500003435363738394142434445464748494AED +:100510004B4C4D4E4F505152535455565758595AB3 +:10052000000000000000F03F0000F0BF0000244089 +:100530009A647EC50E1B514A84D797412E00000055 +:100540006F12033A00007A44200400206C6F61644B +:100550000000000057726F6E67206E756D626572E5 +:10056000206F6620617267756D656E74732C206EE6 +:1005700065656473206964782074687220726F6C9A +:100580006C207069746368207961770D0A0000003F +:10059000437573746F6D206D697865723A200D0A2A +:1005A0004D6F746F720954687209526F6C6C095008 +:1005B00069746368095961770D0A00002325643A5C +:1005C000090000002573090025730D0A00000000D2 +:1005D00053616E69747920636865636B3A09000042 +:1005E0000AD7233C4E470900FAA006F075FC641CAC +:1005F000032CFFF679AFAFF2400013E72021384615 +:1006000008F07FFB00283FF40FAF401C054608F0C0 +:1006100081FBF14EC7B2002456F8241031B13A469E +:10062000284608F07FFB18B1641CF5E7EBA0F9E65B +:10063000204601F032FD56F82410EEA008F0CCFA66 +:10064000AFF22410FFF797FEEEE60C21EEA008F0C3 +:10065000C3FAE9E610B5F6A006F03EFC012000F072 +:10066000AAFEFAA006F038FC0A2006F083FABDE8DC +:100670001040002006F024BB10B5F8A006F02CFCBA +:10068000002000F068FDF8A006F026FC0A2006F025 +:1006900071FABDE81040002006F012BB10B5044608 +:1006A000F5A006F019FC3021F94808F0EFFAF948F6 +:1006B00000210160F84801702046BDE81040DBE7EA +:1006C0002DE9F047064608F025FB054600F0D3FE6D +:1006D000DFF8049307464FF0010809F14C0955B1C2 +:1006E0002A46EEA1304608F01DFBC8B1307800273D +:1006F0002D2824D026E0EBA006F0EEFB0024454692 +:100700004FEA090656F8241041B105FA04F03842C0 +:1007100002D0E9A008F060FA641CF3E7B9A01EE07B +:10072000E6A006F0D9FB00244FEA090555F824108D +:100730000029F3D0E0A008F04FFA641CF6E7012787 +:10074000761C6D1E5FF0000459F8241031B12A4662 +:10075000304608F0E7FA30B1641CF5E7DDA0BDE8EB +:10076000F04706F0B9BB08FA04F01FB100F07EFEB6 +:10077000DFA002E000F031FDE0A006F0ADFB59F88B +:100780002410AFF2BC10BDE8F04708F025BA70B5F0 +:100790000024DDA006F0A0FB8F4DAC3504EB440037 +:1007A00005EB80014A6855F82010DDA008F014FA26 +:1007B000641C0B2CF2D370BD3EB5054608F0AAFAB6 +:1007C00008281DD10024285D08F01EFA2855641C55 +:1007D000082CF8D30024D448295D08F092FA28B1F7 +:1007E0002819295D401C08F08CFA18B1CFA006F03A +:1007F00073FB3EBD641C082CEDD3284600F024FC9E +:10080000D2A006F069FBC84BD64A002069461518ED +:100810001C5C95F88C50401C08284C55F7D30022DE +:100820000A54AFF25C2008F0D7F93EBD2DE9F04143 +:10083000804608F06FFACB4F674D10F0FF0612D0DC +:10084000324696A1404608F06DFA98B15FF0000478 +:1008500055F82410E9B13246404608F063FAE8B191 +:10086000641CE4B2F4E7787905EB800050F8041CCE +:10087000BDA018E0C1A006F02FFB002455F82410FD +:1008800029B18DA008F0A8F9641CE4B2F6E75DA0D8 +:1008900000E052A0BDE8F04106F01EBB601C78717C +:1008A00055F82410BAA0BDE8F04108F095B97CB520 +:1008B00004460D4600790021062814D2DFE800F036 +:1008C00003060A0D111EA06801780CE0A06890F9DB +:1008D000001008E0A068018805E0A068B0F90010E9 +:1008E00001E0A0680168AFA008F076F9002D04D0FF +:1008F000D4E90312ACA008F06FF97CBDA06869468A +:100900000068FFF7CDFC0146A9A008F065F9002DAD +:10091000F3D0E06808F08EFC6946FFF7C1FC0146A1 +:10092000A4A008F059F9206908F084FC6946FFF793 +:10093000B7FC01469FA008F04FF97CBD2DE9F047B8 +:10094000814608F0E7F99C4D060029D0012E03D11D +:1009500099F800002A2823D098A1484608F0AFF95A +:10096000002834D0401C044608F0F5F982462046A1 +:10097000FFF7ECFB8046002606EB860705EB8704B5 +:1009800055F8270008F0C6F9024655F827104846E2 +:1009900008F0C8F9E8B1761C622EEDD388A061E1B9 +:1009A0008FA006F099FA002404EB840005EB800781 +:1009B00055F8201090A008F00FF931463846FFF79F +:1009C00076FF10A006F088FA641C622CECD3BDE818 +:1009D000F08715E14F4B0900F0AB0008496E7661D6 +:1009E0006C6964206D6978657220747970652E2E4B +:1009F0002E0D0A004C6F61646564202573206D69BB +:100A0000782E2E2E0D0A00004D6F746F72206E75B9 +:100A10006D626572206D7573742062652062657405 +:100A20007765656E203120616E642025640D0A00B3 +:100A3000526573657474696E6720746F20646566AF +:100A400061756C74732E2E2E0D0A00005265626F54 +:100A50006F74696E672E2E2E000000005361766958 +:100A60006E672E2E2E0000000D0A5265626F6F74A5 +:100A7000696E672E2E2E00000D0A4C656176696E38 +:100A80006720434C49206D6F64652E2E2E0D0A00A1 +:100A9000F003002000000020950100206C697374B1 +:100AA00000000000456E61626C65642066656174DB +:100AB000757265733A2000002573200041766169E4 +:100AC0006C61626C652066656174757265733A204D +:100AD00000000000496E76616C696420666561748F +:100AE000757265206E616D652E2E2E0D0A00000058 +:100AF00044697361626C656420000000456E616248 +:100B00006C65642000000000417661696C61626C74 +:100B10006520636F6D6D616E64733A0D0A000000AD +:100B200025730925730D0A00C8B400084D75737448 +:100B300020626520616E79206F72646572206F6635 +:100B40002041455452313233340D0A0043757272DC +:100B5000656E742061737369676E6D656E743A209B +:100B6000000000002004002043757272656E74203E +:100B70006D697865723A2025730D0A0041766169C6 +:100B80006C61626C65206D69786572733A20000053 +:100B90004D697865722073657420746F2025730D1C +:100BA0000A00000025640000202564202564000060 +:100BB000257300002025730020AD00083D000000D3 +:100BC0004552523A20556E6B6E6F776E2076617289 +:100BD0006961626C65206E616D650D0A0000000040 +:100BE00043757272656E742073657474696E677391 +:100BF0003A200D0A000000002573203D200000006F +:100C000006EB860605EB8607F86808F013FB4146FD +:100C100008F0AAFB25D8386908F00CFB414608F01B +:100C2000ADFB1ED83979052907D0504606290ED2CA +:100C3000DFE801F0050508080B0B4046F6E7A16860 +:100C4000087004E0A168088001E0A168086055F818 +:100C5000261096A007F0C0FF2046BDE8F04700210F +:100C600025E695A0BDE8F04706F036B92DE9F0413C +:100C700005F072FF4FF47A71B0FBF1F198480378F8 +:100C80009848027898A007F0A7FF00F0CBFB064633 +:100C9000A548A6490068B0FBF1F1A5A007F09CFFAC +:100CA0000024AB4F012500BF57F8241051B105FABD +:100CB00004F0304203D0AFF2002007F08DFF641C37 +:100CC000E4B2F1E7012000F09BFB40B1A149A0484C +:100CD0000978183050F821109FA007F07DFFAFF27F +:100CE000DC2006F0F9F805F08DFB02469D480188EE +:100CF000BDE8F0419CA007F06FBFA4A006F0ECB8DF +:100D00002DE9FF5FDFF8B49299F8000038B90121AE +:100D100089F80010AAA006F0DFF800F0C3F8DFF8A9 +:100D2000D8A2DFF8D8B200BF06F0A6F800286ED02F +:100D300006F0B8F8092806D03F2804D0DAF80010E9 +:100D40005446B1B34DE00024814F25462C3707F1BE +:100D50008408DAF800600BE0DAF8002022B1A74836 +:100D6000396807F0DFFF10B904B93C463D460C373F +:100D70004745F1D39CB150465F46016822682B6815 +:100D8000525C5B5C9A420AD11AB17A54491C0160E8 +:100D9000F3E720220BF80120491CCAF80010DAF80A +:100DA0000000574608B1AC4210D095A006F094F868 +:100DB00007E014E0206806F08FF8092006F07FF8BD +:100DC0000C34AC42F6D900F06DF800265C46386869 +:100DD0008642A9D2A05D06F072F8761CF7E70428D7 +:100DE00010D00C2814D019B10A2815D00D2813D012 +:100DF0007F283FD0302997D2202895D37E2893D8BA +:100E0000B9B345E004B07D48BDE8F05F46E447E093 +:100E10007DA006F061F829E0AFF2184006F05CF81A +:100E2000206800254A490BF800507A48CDE9000BAC +:100E30005E460C230B222C31029501A807F0EAFE36 +:100E4000070007D0386807F065FF3044B968401CD8 +:100E5000884702E070A006F03FF83021674807F0AD +:100E600015FF256099F80000002819D000F01AF845 +:100E70005AE70BE00029FBD0491E0020CAF80010F9 +:100E80000BF801006DA006F027F84DE72028EFD001 +:100E90000BF80100491CCAF8001006F010F843E7EF +:100EA000BDE8FF9F66A006F017B800002573207309 +:100EB000657420746F2000004552523A2056616CD0 +:100EC00075652061737369676E6D656E74206F75EB +:100ED00074206F662072616E67650D0A0000000065 +:100EE000470100209800002053797374656D2055E8 +:100EF0007074696D653A202564207365636F6E6454 +:100F0000732C20566F6C746167653A202564202A23 +:100F100020302E3156202825645320626174746578 +:100F20007279290D0A000000BC03002040420F0026 +:100F30004350552025644D487A2C206465746563C0 +:100F40007465642073656E736F72733A20000000DD +:100F500070AC00085001002041434348573A202517 +:100F6000730000009A0000204379636C6520546987 +:100F70006D653A2025642C20493243204572726FFA +:100F800072733A2025640D0A000000004166726FFA +:100F9000333220434C492076657273696F6E20327C +:100FA0002E31204A616E2020352032303133202FFF +:100FB0002031303A31313A323800000095010020BA +:100FC0000D0A456E746572696E6720434C49204D69 +:100FD0006F64652C207479706520276578697427A3 +:100FE00020746F2072657475726E2C206F722027CA +:100FF00068656C70270D0A0000000020F0030020D7 +:101000000D1B5B4B000000001B5B324A1B5B313B3E +:10101000314800005D0300084552523A20556E6B7E +:101020006E6F776E20636F6D6D616E642C207472CD +:1010300079202768656C70270000000008200800F0 +:101040000D0A2320000000002DE9F041054604466A +:10105000F64EF74F09E0F54807F053FE20B1611B4B +:10106000801B384480F88C10641C21780029F2D150 +:10107000BDE8F0812DE9F05F4FF4E472ED49EC48F2 +:1010800007F0EBFDEA49EC4E002091F82D2091F895 +:101090002C4040F6C41500BF00FB00F3193B53433E +:1010A00003F6C4134343634393FBF5F326F8103070 +:1010B000401CC0B20628EFD391F82E3091F82F5083 +:1010C000B1F8A620B1F8A4C0DFF870A300204FF05B +:1010D0000A0B4FF47A7EC5F1640903EB8308A2EB97 +:1010E0000C0600BF00EB8002C3EB42040122002C7F +:1010F00003DDC3F16402D2B201E000DA1A4604FB58 +:1011000004F705FB07F702FB02F297FBF2F707EB88 +:10111000090202FB04F292FBFBF202EB480212B25C +:1011200006FB02F292FBFEF262442AF8102000F164 +:101130000100C0B20B28D5D3B1F8C800B1F8CA205D +:10114000904203D3B1F8CC20904200D91046A1F8C8 +:10115000C800BDE8F09F2DE9F041B949B44C4FF407 +:10116000E4760978217080466680BE2100202171D6 +:10117000EF2184F8C411214684F8C50101F5E47219 +:1011800003E000BF11F8013B58409142FAD384F8C4 +:10119000C50107F061FB342007F0C8FBA54F3846B6 +:1011A00007F088FB042809D10025E819615907F0E8 +:1011B0009DFB042802D12D1DB542F6D307F052FB4A +:1011C000FFF758FFB8F1000F06D0BDE8F04101224B +:1011D00014210F2001F0F8B94AE795498A680243C3 +:1011E0008A6070472DE9F84F90484FF4E471D0E9D8 +:1011F00003B290F814A08E48009207F047FD904883 +:101200008B4C002500782070032060710220A560BF +:10121000FFF7E3FF2820A0734FF01E0884F8188022 +:10122000172084F822002821E17384F819801034F3 +:101230001021E074552020702D20A07261700F21C4 +:10124000E172072161750B21A1701426E670082157 +:101250006173E0750E202071641D50206672E07489 +:10126000462020700A27A772641C2820E67420708C +:101270005A20A0754120E0754FF0320984F818908B +:10128000C4F830B0009A626384F838A084F839500A +:10129000042084F83A0084F83B703E344FF4C87A56 +:1012A00004F8029CA4F802A02A20208001202072C9 +:1012B000152060726348E06063482061202020753B +:1012C000624860606E2084F834002B2084F835007A +:1012D000212084F836005EA0FFF7B6FE84F8426055 +:1012E00040F2DC50A4F8440040F24C41A4F846100F +:1012F000703440F26C7124F8281C243CC82304F894 +:10130000017C23704FF49661618040F27E41A180A0 +:1013100040F23A71E18024344FF47A7124F81C1CB5 +:1013200024F81AAC24F8189C0121A170A0804FF475 +:101330007F71E1804FF4FA6222816181A081E281B4 +:1013400021826082A2824FF0010C84F816C04FF017 +:10135000FF0C84F817C04FF0010C84F818C084F813 +:1013600019C0A776E77684F81CC0E18322846084E4 +:10137000A184E284208584F82A504FF4E130E062B1 +:10138000238684F8326084F83380012184F8341095 +:101390006421E1864FF496712187E063C43C00200C +:1013A00004EB0011401CC1F804510C28F8DBBDE827 +:1013B000F84F0020CFE630B41E49214C00220B78B4 +:1013C00025781446AB4214D14B88B3F5E47F10D195 +:1013D0000B79BE2B0DD191F8C431EF2B09D101F55A +:1013E000E47300BF11F8015B6A409942FAD302B975 +:1013F0000124401E044201D130BCF3E630BC7047EA +:101400000F494968014201D0012070470020704710 +:101410000B494A6802434A60704709494A68824357 +:101420004A6070470648406870470000C8B400082A +:101430002004002000FC0108C0070020CC07002089 +:10144000040000209A99193FF6287C3F03141400E9 +:101450004145545231323334000000000749896855 +:10146000014201D00120DFE70020DDE703498A685F +:1014700082438A60D8E701488068D5E720040020CD +:1014800070B5FE48008807F0DEFE0446FC4907F010 +:10149000C7FC07F0EEFEFB4D21466880FA4807F0D6 +:1014A000F5FCFA4907F0F2FCE8630420FFF7A8FF17 +:1014B000002803D0BDE8704002F0DFBA70BD2DE90E +:1014C000F04F91B0D0E900458046866848680F46E5 +:1014D00080F0004008F0D6FC8346786880F0004039 +:1014E00009F082FA8246386808F0CCFC019038682E +:1014F00009F07AFA8146B86808F0C4FC0390B8682D +:1015000009F072FA02905946039807F089FC079097 +:101510000199039807F084FC07465946029807F0A2 +:101520007FFC06905046039907F07AFC08905046DD +:10153000029907F075FC0390DDE9011007F070FCDB +:101540000E9089F000400C904946089807F068FC1E +:10155000069907F05FFC0D904946039807F060FC80 +:10156000079907F005FC02905146019807F058FCD6 +:1015700004904946079807F053FC039907F0F8FBDD +:1015800082464946069807F04BFC089907F042FC52 +:1015900000905946019807F043FC83463046514677 +:1015A00007F03EFC824628460D9907F039FC81463B +:1015B0003946204607F034FC494607F0D9FB51462E +:1015C00007F0D6FBC8F800003046009907F028FC69 +:1015D00081462846029907F023FC074620460E99CB +:1015E00007F01EFC394607F0C3FB494607F0C0FB75 +:1015F000C8F804003046594607F012FC0646284653 +:10160000049907F00DFC054620460C9907F008FCEC +:10161000294607F0ADFB314607F0AAFBC8F80800E1 +:1016200011B0BDE8F08F2DE9F04F89B0002605F02C +:101630007EFA944C0546E069281A07F004FE9449A6 +:1016400007F0EEFB0390DFF83CA2E5610AF1580ACF +:10165000904D00244FF07E580AF106098948523017 +:1016600030F9140007F0E6FD039907F0D9FB06A94D +:1016700041F8240095F8500010B307F0E4FD01464E +:101680004746404607F002FC83463AF9140007F04B +:10169000D1FD594607F0C4FB02903946584607F081 +:1016A000BCFB7D4F57F8241007F0BAFB029907F0F6 +:1016B0005FFB47F8240007F0DCFD29F8140003E085 +:1016C0003AF8141029F8141095F8510007F0BBFDF2 +:1016D00001464746404607F0D9FB83463AF91400D5 +:1016E00007F0A8FD594607F09BFB02903946584683 +:1016F00007F093FB684F6C3757F8241007F090FB06 +:10170000029907F035FB47F8240039F9140000FB73 +:1017100000660420FFF774FE641C032C9ED3642033 +:101720004643564806A90088404396FBF0F407F16B +:101730000C00FFF7C4FE0420FFF762FE20B106A9EB +:10174000A7F17800FFF7BBFEB9F900004F4600286B +:1017500000DC4042DFF82C915049B9F90220904258 +:101760000CDAB7F90200002800DC4042904205DAAA +:10177000B7F90400002801DD012000E00020464EFA +:10178000253C783648739F2C02D310F0FF0F22D0EF +:101790000024B5F8560007F056FD8246414607F092 +:1017A000E7FA0146404607F071FB804637F914001E +:1017B00007F040FD054656F82410504607F030FB70 +:1017C000294607F0D5FA414607F02AFB46F82400DF +:1017D000641C032CEAD30420FFF712FE2E4C0C3CB1 +:1017E000E8B1DFF8A080DFF8B8A0DFF8B8B00025D6 +:1017F00008F1640838F9150007F01CFD074654F895 +:101800002500514607F00CFB394607F0B1FA59465E +:1018100007F006FB44F825006D1C032DEAD3B168E0 +:10182000306800F0E1FA174D14352880B0680146A1 +:1018300007F0F6FA80467068014607F0F1FA0746AD +:101840003068014607F0ECFA394607F091FA414654 +:1018500007F08EFA09F0B5F980F00041706807F0E2 +:1018600015FB08F051F9104907F0DAFA07F001FD0D +:1018700068800420FFF7C4FD002817E0580100200D +:101880007593D83E0C0000200AE81C4100401C461D +:101890005344923120040020F4050020B0070020BA +:1018A000000048435E06A33B4C3D0FC437D0A568FB +:1018B0007068294607F0B4FAB76880466168384610 +:1018C00007F0AEFA414607F0A5FA8046384621688F +:1018D00007F0A6FA04462946306807F0A1FA214627 +:1018E00007F098FA414600F07FFAFE4C07F0A2FCA0 +:1018F000D9F8101007F03CFA07F0BBFC00B20A213F +:1019000090FBF1F000B22080B42802DDA0F5B470A5 +:1019100004E010F1B40F02DA00F5B470208009B0D1 +:101920007FE62DE9FF5F0120FFF76AFD18B101F0A6 +:1019300074FFFFF778FE02F08BF8EB4D00246F4642 +:10194000A24605F1060B00BF35F8140027F8140075 +:101950000120FFF755FD08B92BF814A0641C032CD7 +:10196000F2D305F0E4F8E04E523EB06100F056FECE +:1019700005F0DDF8B16940F28A24401AA04204D98A +:10198000DA490888401C088005E005F0D0F8B16904 +:10199000401AA042F9D302F05BF8A846B946D24DEE +:1019A00000240327B5F1120538F8141039F8140093 +:1019B000084401B202A820F81410CB480C3830F9C2 +:1019C00014200A4492FBF7F201EBD17125F81420A0 +:1019D000491020F814100120FFF712FD08B92BF868 +:1019E00014A0641C032CDFD34020FFF737FDC0494F +:1019F00000B3BD4A483A107828B9886D010C1170BF +:101A0000010A51709070B8490020891F135C35F9A4 +:101A1000104031F910605F1E06FB0744641C94FB04 +:101A2000F3F325F8103021F81030401C0328EDD3D3 +:101A3000BDE8FF9F48790128FAD1B5F90400B6F94D +:101A4000081000EB410090FBF7F0A8803081EFE731 +:101A5000002801DD024600E042428A4201DA00200D +:101A60007047002802DDA0EB010001E0F8DA08442D +:101A700000B2704770B50446084607F0DBFB054628 +:101A80004FF400062946B44201DB204601E084F011 +:101A9000004007F069FC01D200240EE0B44204DBF0 +:101AA0002146284607F0B9F906E014F1FF4F04D3A8 +:101AB0002146284607F05CF90446204670BD70B503 +:101AC0008C49A1EB6004214607F0AAF9214607F0F2 +:101AD000A7F9894907F0A1F905464FF0FF312046E3 +:101AE00007F014FA2946BDE8704007F099B92DE9CE +:101AF000FC5F7D4C8148523C46F2A8120068216A86 +:101B0000411A91427EDB20628946216B0A2091FBBB +:101B1000F0F07B4B94F9002000B223F81200616AC8 +:101B2000521C0844724991F85D7092FBF7F507FB6F +:101B3000152533F91530C61A50B2666220708742F7 +:101B400001D1002020700D6E884629464FF07E504E +:101B500007F060F98246781E07F06CFB07463046B6 +:101B600007F068FB674907F05BF9394607F08EF923 +:101B7000514607F055F90646606B07F05BFB2946B6 +:101B800007F04EF9314607F0F3F807F072FB606397 +:101B9000A16B081A5C49884202DB4942884200DD99 +:101BA000084600B20A21FFF753FF98F8113064226B +:101BB000434393FBF2F26FF09505AA4201DA2A46FD +:101BC00004E043F6FB25AB4200DD962212B2A28070 +:101BD00098F81B104143322091FBF0F1E088084453 +:101BE00000B24A49E080884202DB4942884200DD77 +:101BF0000846E0804FF4FA7190FBF1F01044A080A9 +:101C00003F4D00E0EEE06C35286807F032FB00FB4A +:101C100000F6686807F02DFB00FB0066A86807F077 +:101C200028FB4043304407F005FBFFF748FF074619 +:101C300037480088019007F006FB0090A5F10C06DC +:101C4000A968B06807F0ECF883466968706807F027 +:101C5000E7F882462968306807F0E2F8514607F055 +:101C600087F8594607F084F8394607F0D9F8009903 +:101C700007F0D0F807F0FDFA98F85220019900B269 +:101C8000B1FBF2F1454609B2FFF7E2FE214F0646ED +:101C90003880484607F0D7FA8046304607F0CAFA3F +:101CA000E16B07F0BDF8414607F0BAF8A16A07F00A +:101CB0005FF8A0621849404607F0E8F80646E16A76 +:101CC000606B401A07F0B6FA314607F0DFF81349A7 +:101CD000884202D81249884200DD08460A21FFF7EF +:101CE000C9FE1FE0900100205E000020400100209E +:101CF00020040020DF59375F00004040B80000207A +:101D00000006002000002041D4FEFFFFD08AFFFF24 +:101D1000580100200601002000247449000096C3E9 +:101D2000000096438046606BE062404607F0A1FAEF +:101D300078806E6E4FF07E50314607F06BF841466A +:101D400007F06EF880463146A06A07F069F8414610 +:101D500007F00EF80646A06207F08BFAB88005215E +:101D60003046FFF787FE064695F8250007F06BFA28 +:101D7000314607F055F8214E314607F087F82049E3 +:101D8000884212D80521A06AFFF774FE804695F8B4 +:101D9000250007F058FA414607F042F8B0463146B0 +:101DA00007F074F81749884201DD08460EE0052166 +:101DB000A06AFFF75FFE064695F8250007F043FA94 +:101DC000314607F02DF8414607F060F80546B4F9B2 +:101DD000040007F02FFA294607F01CF807F049FA2B +:101DE000A080F880BDE8FC9F10B507F021FF0649F0 +:101DF00007F016F807F03DFA00B210BD0000A04150 +:101E0000000016C3000016434C3D0F44084605F081 +:101E100056B81FB504F0B9FE7049002006F0D8FE90 +:101E20000020FFF7C8FAFFF725F96D4C002594F85C +:101E30008B0018B1012820D009281ED08DF80C5035 +:101E400084F88B5003A803F09BFDD4F8000102F046 +:101E500038F80720FFF7DCFA00F0D8F8607901269F +:101E60000E280DD008280BD08DF805504FF4807740 +:101E70003846FFF7F3FA50B905E08DF80C00E1E7BA +:101E80008DF80560F2E70820FFF7E8FA00B10120BD +:101E90008DF802000120FFF7E1FA8DF8010008201B +:101EA000FFF7DCFA80F001008DF800004D48007863 +:101EB00000B101208DF8030094F8E000C0F3C000E9 +:101EC0008DF80400B4F8AA00ADF80800B4F8AC002E +:101ED000ADF80A0094F88B00012812D0092813D01D +:101EE0008DF80650684604F0FDFC404D3E482860E1 +:101EF0000820FFF7B3FA58B103F075FA3C482860A0 +:101F00000EE08DF80660EDE707208DF80600E9E7A2 +:101F10003846FFF7A3FA18B1D4F8F00003F0E6F85A +:101F20000120FFF79BFA30B14FF48060FFF796FA7B +:101F300008B101F0F1FE2F494FF01008C1F8008000 +:101F4000A1F1040A4FF0080BCAF800B00025AAF16D +:101F500004098F14D9F8001081F01001C9F800109D +:101F6000D9F8001081F00801C9F80010192004F018 +:101F700001FE21480760192004F0FCFD1E48001FE7 +:101F800007606D1CEDB20A2DE4D3CAF800B0CAF8A0 +:101F9000008001F07DFAFFF773FA0220FFF75EFA86 +:101FA00008B101F02EFB04F0C2FD1449086060790D +:101FB000052803D112494FF4C870088011494FF425 +:101FC0007A7008801048467300F05FFDFCE7044813 +:101FD000B0F9A80000F0C9F8FEE700000D1E0008E7 +:101FE000200400207F000020A7290008C000002056 +:101FF00011540008140C014014080140BC000020DA +:102000005401002056010020B00700202DE9F041C6 +:10201000FE4DFF4EFF4C687906EBC00040786070C3 +:102020002020FFF71BFA08B1012060706879FA4997 +:10203000122809D016F8302006EBC0002270436841 +:10204000002B19D0002025E05FF0000005EB001305 +:10205000D3F8042112F0FF4F0ED0D3E9427C01EBFC +:102060000016D3F81031F360A6E884102278401CE3 +:10207000521C22700C28E9DBBDE8F08103EB00154F +:1020800001EB001495E8C010ED68401CC4E902C5DE +:10209000C4E900679042F1DBEEE7F0B5401C002197 +:1020A000DA4A0B4602EB0114491CC4F804310C292E +:1020B000F8DBD74B03EBC0014C68002C14D0002197 +:1020C00013F830000EE000BF04EB011302EB011522 +:1020D00093E8C010DB6805F58275491CC5E902C3A9 +:1020E000C5E900678842EFDCF0BDCA4810B540780A +:1020F000002827D0C548C74C4079A41C05280ED01D +:1021000004DC01281BD0042804D112E0082806D0E2 +:102110000E2817D02020FFF7A1F9002812D021881F +:10212000002004F065FC61880120BDE8104004F047 +:102130005FBC2189002004F05BFC6189F4E76189C0 +:102140000020F2E710BD70B5B34E0024183EB14D2B +:1021500007E000BF36F81410204604F03DFC641C74 +:10216000E4B228788442F5D370BDAA4AAA4B002174 +:102170001278183B04E000BF23F81100491CC9B2D3 +:102180009142F9D3DFE72DE9FF5FA24EDFF88CB271 +:102190003578032D24D9A248BBF90420B0F90400F6 +:1021A0004142002801DD034600E00B466FF0630763 +:1021B000FB1A9A4204DA002800DC08463A1A0DE0BD +:1021C000002801DD034600E00B4664339A4205DD3A +:1021D000002801DD024600E00A466432ABF8042024 +:1021E000DFF828928E48012D99F9C660B0F90600F3 +:1021F00000908A48B0F90270B0F900A034D90024E8 +:10220000A8462FE0BBF90400704307F013F8824999 +:1022100001EB0415E96806F003FE0390504607F051 +:1022200009F8696806F0FCFD0290384607F002F8EC +:10223000A96806F0F5FD0190009806F0FBFF2968FB +:1022400006F0EEFD019906F093FD029906F090FD6F +:10225000039906F08DFD07F00CF86F49183921F845 +:102260001400641C4445CDD36A4C4D4699F80500D2 +:10227000A41CDFF8B091052836D004DC012823D057 +:10228000042862D102E008285FD19FE0BBF9043046 +:102290004FF47F7206FB037101F2DC514FF4FA60D8 +:1022A000914201DA114602E0814200DD01462181BE +:1022B0005E43F11B01F2DC51914201DA104601E06C +:1022C00081420FDD608140E0B5F8C810BBF9040021 +:1022D00006FB0010B5F8CA10884203DBB5F8CC1035 +:1022E0008842EFDD0846EDE74F4A15F9DE0FB2F9F7 +:1022F00002102B8948434A49B1F902603344C6179A +:1023000000EB167003EB2010AB88DE3D984203DB38 +:10231000B5F8E430984200DD1846208095F9DF00DA +:10232000B2F90020B1F900105043B5F8EC20114487 +:10233000C21700EB127001EB2010B5F8E8108842CC +:1023400063DBB5F8EA109FE060802020FFF786F895 +:1023500000286FD095F8E01000208A0707D0B9F860 +:102360000C20B5F89830A2EB030262F30F004A0785 +:1023700007D4B9F80E20B5F89830A2EB030262F347 +:102380001F40B5F8E620024412B22280B5F8EC30C6 +:1023900003EB104003B2254863800079A0B3C80660 +:1023A00078D5214A95F9DF00B2F902304142B2F9FD +:1023B000002059435043CA1701EB12710911C2178B +:1023C00000EB1270A1EB2010208079E012490098F8 +:1023D00018390E4A08801648DA32867A92F90010C7 +:1023E00092F9023092F9010092F9032056B3B9F93B +:1023F0000270B5F898C0A7EB0C0707FB01F8B9F914 +:102400000010A1EB0C0116E05BE040E0200400208E +:10241000D0B800087E0000209006002000010020B7 +:102420000E0100203001002020000020E2070020E3 +:10243000B00700205DE003FB0183474302FB01700E +:10244000238006E0794303FB0A11784302FB0A006C +:1024500021806080B4F90000B5F8D0100144B5F8CF +:10246000CE00814204DBB5F8D200814200DC084690 +:102470002080B4F90200B5F8D6100844B5F8D4109D +:10248000884204DBB5F8D81088427FF75DAF084674 +:102490005AE7FFE7484995F9DE00B1F90260704359 +:1024A000C61700EB167002EB2010208095F9DF00B4 +:1024B000B1F900104843C11700EB117003EB201075 +:1024C0006080B4F90000B5F8E210884203DBB5F88B +:1024D000E410884200DD08462080B4F90200B5F817 +:1024E000E810884203DBB5F8EA10884200DD0846B0 +:1024F000608095F8E000000712D500262020FEF746 +:10250000ADFF00B1022600244FEA090707EB4400A3 +:102510000189A019C0B204F06BFA641C042CF5D335 +:10252000264E27490120B6F900700B7806E000BF5F +:1025300036F91020BA4200DD1746401C9842F7D306 +:102540000024884632E000BFB5F8A600B84205DA9C +:1025500036F814103A1A891A26F8141036F914109D +:10256000B5F8A420914201DA104602E0814200DC75 +:10257000084626F81400B9F90600B5F89A10884202 +:1025800008DA1020FEF76AFF40B1B5F8A80000BFD6 +:1025900026F814000B48407818B106E0B5F8A400FE +:1025A000F6E7B5F8A80026F81400641C98F80000B7 +:1025B0008442C9D3BDE8FF9F200000207806002098 +:1025C0007E000020B00700202DE9F74FDFF848A477 +:1025D000904607460025DFF83C944FF48056AAF158 +:1025E000040B17E000240EE0D9F8001081F0080178 +:1025F000C9F80010CAF80060019804F0BBFACBF8E3 +:102600000060641CE4B2BC42EED33C2004F0B2FA99 +:102610006D1CEDB24545E5D3BDE8FE8F2DE9FC5FAD +:10262000FE4F002440F2DC50B7F90610FC4D4FF489 +:10263000FA73814201DA64260DE0F948B1F5FA6FC8 +:1026400090F8320004DAA1F2DC52504390FBF3F030 +:10265000C0F16400C6B2AA4695F894E095F895B02A +:10266000B5F898500022ED4840F2E63CD14630F9EA +:102670001270781B00F2F313634503D8002803DCC3 +:10268000E81B01E04FF4FA7080B2022A3BD0BEF1A1 +:10269000000F06D0864503D2A0EB0E0080B200E00A +:1026A00000206423B0FBF3F3DFF878C30CEB43089E +:1026B0003CF913C0B8F90280CDF800C0A8EB0C0CAF +:1026C0006FF0180803FB08F300EB83030CFB03FC1B +:1026D00064239CFBF3F3DDF800C06344DFF83CC3E4 +:1026E000ACF1220C2CF8123099F8303043434FF4FF +:1026F000FA70B3FBF0F0C0F16400C0B27043642321 +:10270000B0FBF3F015E0BBF1000F06D0834503D218 +:10271000A0EB0B0080B200E00020C04B223B988071 +:1027200099F8313043434FF4FA70B3FBF0F0C0F145 +:10273000640009EB0203C0B293F80EC04FF06409C5 +:102740000CFB00FCBCFBF9FCDFF8D082A8F17E0892 +:1027500008F802C093F822304343B3FBF9F308F1C1 +:102760000300AF42835405DA593030F812305B422F +:1027700020F81230521CD2B2032AFFF474AFBAF818 +:102780009A00814201DA014604E04FF4FA6399426B +:1027900000DD194689B2091A4FF47A725143C0F527 +:1027A000FA60B1FBF0F081B26422B1FBF2F09D4B14 +:1027B0006FF018060C3303EB400533F9103070430B +:1027C000B5F9025001EB8000ED1A454395FBF2F09C +:1027D000DFF84882934EA8F122081844103EA8F86A +:1027E0000600707AD146A8F17E05E8B38E48B0F9AC +:1027F0000010B5F91A00081A06F01CFD8B4906F006 +:102800000FFB8B4906F042FB074607F03BFB834674 +:10281000384608F0E9F882464746B8F9000006F065 +:1028200009FD5146019006F0FBFA8046B7F9020017 +:1028300006F000FD5946009006F0F2FA414606F017 +:1028400097FA06F016FD80465146009806F0E8FA21 +:1028500082465946019806F0E3FA514606F0DAFA44 +:1028600006F007FD388000E001E0A7F802800220B2 +:10287000FEF7F4FD002760B3E878401CC0B20621E3 +:10288000B0FBF1F2E87001FB1200C8B9002003F0C0 +:10289000E9F82979634A01F00703703A491C22F8E4 +:1028A000130029715FF0000032F81010401C214421 +:1028B000C0B28CB20828F7D3E00800F08AFE287274 +:1028C000287A298C884203D899F88A10814201D944 +:1028D000AF7001E00420A870A87802F053FE5548BC +:1028E0004C4C008818B10120FEF78AFD10B95248FF +:1028F000008820B1206880F00800206014E0B178E2 +:10290000082011B14349091D0860717811B141498E +:10291000083108604FF40060FEF7A0FD20B1707828 +:1029200000B1012002F034FF8020FEF797FD48B18E +:10293000E96BA86A411A05D44CF250310844E863A7 +:1029400004F090FBA96BA86A411A03D4717BF9B11A +:102950000120B07001F03EFD1020FEF751FD68B17E +:10296000296CA86A411A09D4697A052906D3334922 +:1029700008442864206880F0100020603048C16856 +:1029800000290ED002B02548BDE8F05F8438084722 +:10299000B770216881F0080121602A490844A863C2 +:1029A000D8E7BDE8FC9F10B51D4C204490F88C0082 +:1029B00004F040F8A0F2EE2140F2DD52914201D342 +:1029C000B4F8980010BD2DE9F047144EDFF854809C +:1029D000A03EA8F160087079104F401C002470716F +:1029E000A14608F14005316B20468847727908EB13 +:1029F000C40102F0030221F8120025F8149000200F +:102A000035F8143031F81020401C1A4425F81420F1 +:102A1000C0B219E00C0C0140140801403001002044 +:102A200020040020C007002090010020DB0F494057 +:102A3000000034435401002056010020F0490200F8 +:102A40006408002020A107000428D9D335F9140018 +:102A5000801CC11700EB9170801025F8140037F925 +:102A60001410C91E884202DA811C27F8141037F9A5 +:102A70001410C91C884202DD801E27F81400641C53 +:102A8000E4B2082CAFD3BDE8F0872DE9F04F002069 +:102A900085B0824683460646039002F0B6FC08B134 +:102AA000FFF791FFDFF8F493FD4C4FF00005D9F8E4 +:102AB0002810D9F84800081A6FD444F6206211444F +:102AC0000820C9F84810FEF7C9FC08B9FFF77BFFDA +:102AD0004FF40070FEF7C2FCDFF8C0E30EF1A00E69 +:102AE00080B3DFF8C083B9F90C1098F89FC00CEBE5 +:102AF0008C038B421EDA6078E0B1B8F99870002040 +:102B00004FEA0E0222F81070401CC0B20328F9D31D +:102B1000B8F8A200AEF8060098F8A000604400EBF8 +:102B2000800248468A4201DA65702570C289521CCB +:102B3000A9F80E208B4202DA627802B92570491C8E +:102B4000A9F80C10D5480127A030B0F906C0D54827 +:102B5000B0F89A108C456FDAD0486A30058045800D +:102B60008580263800F15C080580458099F80620AC +:102B7000521CD2B289F80620B8F90400884205DA5E +:102B8000B8F90200884201DA607838B10420FEF713 +:102B900065FC78B3607880B13AE005E2142A0BD185 +:102BA000C1484FF47A7101804FF48070FEF756FCF3 +:102BB000002801D001F01CFFCCE0BA48B8F904208D +:102BC0004146B0F89A309A4222DAB1F90220B0F8C0 +:102BD0009C0082421CDDB8F90010814218DD99F892 +:102BE00006104846142904D1418A21B14582A9F82A +:102BF0001470AFE00CE0C18B21B10021C18319B189 +:102C0000022102E00121F9E7032189F80010A1E087 +:102C1000A448B0F8761081B1A1483230807938B13B +:102C2000207828B1A14867700188A9F81A108FE0B0 +:102C30006078D8B365708BE039E0B8F90420B0F85B +:102C40009A3041469A4208DB90F89EC0BCF1010FD1 +:102C50000BD1B1F900C09C4507DA63782BB199F824 +:102C60000600142876D1657074E0B0F89C309A4262 +:102C700007DCB1F900209A426ADD90F89E00012835 +:102C800066D1B8F90200984262DA607870B9864875 +:102C9000008858B9A07848B199F80610142959D17C +:102CA000824967700988A9F81A1053E050E07D4AFC +:102CB0007A48B2F89C30A0309C454BDD94F801C0B6 +:102CC000BCF1000F46D1B0F904C08C450FDAB0F961 +:102CD000028088450BDA99F80600142803D1744B5A +:102CE0004FF4C8721A80401C89F8060032E09C45F7 +:102CF0000CDDB0F902C08C4508DA99F806101429E9 +:102D000000D1A773491C89F8061023E0B0F902C06E +:102D10009C4501DD443208E08C4501DA44320AE08A +:102D2000B0F90000984203DD42321088801C04E0B4 +:102D300088420DDA42321088801E10800120FEF792 +:102D40000AFA8020FEF78AFB20B104F0EDF901E0D9 +:102D500089F806500420FEF781FBF8B1B9F81E206F +:102D60004846322182B1627872B14C4AA032B2F93F +:102D700006304C4AB2F89A20934205DD484A323276 +:102D800092790AB90182C583454A3232527A32B108 +:102D9000C28A438A1A4309D1A9F8101006E0418A71 +:102DA00021B1617811B94582A9F81470DFF8ECE01F +:102DB00000200EF1A00E00BF0EEB4001B1F908306B +:102DC00040F214518B4201DA012200E0002200EBB4 +:102DD00040018A40A3F2155CBCF5C77F02D84FF0D2 +:102DE000010C01E04FF0000C01F101080CFA08FCA5 +:102DF00042EA0C0240F2A46C634501DD012300E0CD +:102E00000023891C8B401A433243401CC0B296B247 +:102E10000428D1D3DFF88880002008F13208214946 +:102E200001EB4001B1F86A10314000D0012108F8EF +:102E30000010401CC0B20F28F1D398F8000040B930 +:102E4000184890F89F0000EB8001B9F90C0081420E +:102E50000BDA0120FEF7D4FA38B1E07830B90F4828 +:102E6000443005804580E77000E0E57098F8010087 +:102E700038B1207930B90948443005804580277140 +:102E800000E0257198F8060000B92770E17810205D +:102E900009B9217981B107490FE0000090000020B5 +:102EA000B0070020200400205601002090010020DF +:102EB00054010020140C0140FE4908600220FEF776 +:102EC0009FFA98B198F8020078B1A07970B9FA48E1 +:102ED000FA49A77100680860F948C188F948A9F85B +:102EE00018100580F848058000E0A5710420FEF761 +:102EF00087FAD0B198F8030038B1607930B9F34857 +:102F000067710188F248018000E0657198F80A0055 +:102F100018B1607A10B9677200E0657298F80E0017 +:102F200018B1EA480188A9F81A101020FEF768FACB +:102F300050B3E07A40B399F80900052826D398F8F1 +:102F4000070058B1E07950B9DD49E7711631081F23 +:102F500002F091F9022189F8011000E0E57198F87A +:102F6000080090B1207A78B9D54827720A3000F16C +:102F7000100102680A60406841F8040FD0481A3016 +:102F800002F079F989F8017000E0257298F80900DB +:102F900008B1A77200E0A572CE484079082801D098 +:102FA0000E2816D1657214E099F90700C21700EBDC +:102FB000927222F00302821A00F1010089F80700E0 +:102FC00046D0012A4CD0022A52D0032A59D089F87F +:102FD000075003F0ACFDBF49C9F828004E468A8966 +:102FE00012B1F36CC31A7DD41044F064FEF799FC5F +:102FF00003F09DFDB062B18D411A7181F062042031 +:10300000FEF7FEF918B3AE49B1F9042002F145000C +:103010008A2843D8607998B3AC480388AC480088C4 +:10302000181A00B210F1B40F02DC00F5B47000B24F +:10303000B42802DBA0F5B47000B2637B3BB1A54BB2 +:103040009B7D43431E2093FBF0F0101A888029E0FB +:103050000420FEF7D5F90028BBD000F0A7FDB8E7A3 +:103060000220FEF7CDF90028B3D000F0EBFBB0E76B +:103070000220FEF7C5F90028ABD0FEF738FDA8E71F +:103080000CE00820FEF7BCF90028A2D000F04FFEAB +:1030900091488B490839008888809AE78B480188D5 +:1030A0008B4801800220FEF7ABF9A0B1A07990B166 +:1030B0008349B6F91820B1F90630981A002800DCC7 +:1030C000D01A844B93F89630984200DDA5717E4863 +:1030D00000881044C8801020FEF792F9F0B3E07920 +:1030E00018B900E0C3E1207AC8B3207BB8B3774EAB +:1030F000B6F9000006F09EF8784F394605F090FECC +:1031000007F072FC0190B6F9000006F093F839461A +:1031100005F086FE06F0B6FEDFF8B8810090684F35 +:1031200098F8F700DFF8B8912E3FE8B33E1DB7F9E5 +:103130000200B6F90210401A01F0FBF998F8F710F6 +:10314000494288420DDBB7F90200B6F90210401A75 +:1031500001F0EFF998F8F710884201E063E002E02F +:1031600004DD084609E002F05EF85CE0B7F9020011 +:10317000B6F90210401A01F0DCF971880844708039 +:10318000B7F90000B6F90010401A01F0D2F998F82A +:10319000F710494288420CDBB7F90000B6F900107D +:1031A000401A01F0C6F900E044E098F8F7108842B0 +:1031B00001DD084606E0B7F90000B6F90010401A34 +:1031C00001F0B7F93188084400B2308006F032F8D7 +:1031D0008046019905F024FE0746B6F9020006F084 +:1031E00029F80290009905F01BFE394605F012FE01 +:1031F0004F46494605F04AFE06F03BF8304E4A3E3F +:1032000030804046009905F00BFE8046DDE9011054 +:1032100005F006FE414605F0ABFD394605F036FEE9 +:1032200006F027F870802649B1F90200002814DD65 +:10323000024613E0B7F9000005F0FCFF8046019953 +:1032400005F0EEFD0646B7F9020005F0F3FF029027 +:10325000009905F0E5FD3146C8E742421849B1F949 +:103260000010002901DD0B4600E04B429A4203DDCD +:10327000002806DC404204E0002901DD084600E0A9 +:103280004842DFF83C900FFA80FE94F80480E3781F +:10329000A9F12009002009F1060C13B9B8F1000FBB +:1032A0005ED0022859D206494A3931F910204A31F4 +:1032B00018E00000100C01404000002044000020F5 +:1032C0000E010020120000201000002090010020BC +:1032D00092010020200400207C00002035FA8E3C62 +:1032E0000000204131F9101002EB410261498A428D +:1032F00003DB49428A4200DC11465F4A32F8102063 +:10330000891A5E4A02EB400492F82970B4F84240F0 +:1033100021440EB2517D6424714391FBF4F17C424F +:1033200009B204EB84048C4203DC07EB87048C4273 +:1033300000DA2146524C049134F910103144514EB8 +:10334000B14202DB7642B14200DD314609B224F8D7 +:103350001010D27F5143091303910BB102282FD1D2 +:1033600047493A3131F9102002EB82010C014349FF +:1033700092460E18424AB17B263294FBF1F1424C40 +:1033800032F9107034F91040091B09B239443F4F2B +:10339000B94202DB7F42B94200DD394604F52074B0 +:1033A00022F81010B4F5A06F01D922F8105032F9AC +:1033B00010107D2291FBF2F1327E514341F38F1BBD +:1033C000B8F1000F14D0022812D20499CEF5FA7287 +:1033D00051434FF4FA77039C0AFB0E1162430BFB37 +:1033E0000E2291FBF7F192FBF7F209B212B207E05D +:1033F00023B1022802D2DDE9032101E051465A46F9 +:103400001F4E214C223E502734F91040365C664353 +:1034100096FBF7F61A4F8E1B1437324437F810100C +:1034200027F81040611A39F810703CF810402CF859 +:1034300010703C440C4429F81010114924B21F3973 +:10344000095C614341F34F11511A0D4A2C3222F8A5 +:103450001010401CC0B20328FFF41FAFFEF793FE0C +:10346000FEF743FE05B0BDE8F04FFEF76CBE05B0B9 +:10347000BDE8F08F0CFEFFFF20000020200400209C +:10348000D4000020F0D8FFFF4C00002080C1FFFFD7 +:103490002DE9F843FE4CFF4900252F4694F85C20A7 +:1034A000A1F1100003F0F1FE08B101250CE0F9488C +:1034B00004F093F808B1012706E0F64803F069F834 +:1034C00010B9032003F0D9FBF34E4FF0000800BF02 +:1034D00094F84F0030B1012804D0022814D00328FA +:1034E00028D11FE08DF800804FF44870E949ADF80D +:1034F00002001039684602F049FB08B10120307023 +:1035000094F84F00012815D065B1E24994F85C2089 +:10351000A1F1100003F0B9FE0220307094F84F00C2 +:10352000022812D0DB48103803F059FF10B10320F5 +:1035300030700AE0307840B994F84F0010B184F848 +:103540004F80C5E70120FDF768FFD248103004F036 +:1035500016F938B9CF48103002F0ADFB10B902208F +:10356000FDF75BFF0120FDF74BFF18B1C94810388C +:1035700000688047C7480068804727B1B4F8540006 +:1035800004F044F804E01DB9B4F8540003F017F84F +:1035900002F0A4FC10B90420FDF73FFFB4F940008D +:1035A000642290FBF2F102FB11000CB205F042FE26 +:1035B000BA4905F035FC0546204605F03BFE294694 +:1035C00005F0D6FBB64905F02BFCB6490860BDE80E +:1035D000F88370B50546AE4890F8880005F033FED4 +:1035E0000446284605F02FFEAF4905F019FCAF4907 +:1035F00005F04CFC214605F013FC05F053FE80B2AB +:1036000070BD70B500252C46002002F02BFA054451 +:103610000A2003F0AFFA641C202CF5D3C5F34F1039 +:10362000FFF7D7FF9A4A022192F8893003FB01F491 +:10363000844202D8491C0629F8D39D48017092F8AB +:103640008A0048439B49088070BD3CB50A88ADF8A4 +:1036500000204A88ADF802208A888D4BADF80420FE +:1036600000EB4000002203446C46981834F81250D6 +:1036700090F94600002802DD01EB400002E06D42B7 +:10368000A1EB4000521C20F8025C032AEDDB3CBD9C +:103690002DE9F047DFF80092874E7D4CB9F8042001 +:1036A0000025AAB37B4900204FF4C87C7039C84676 +:1036B000624501D141F8205051F8203036F91070A0 +:1036C0003B4441F8203026F8105004EB4003401CE6 +:1036D0009D860328ECDB012A15D1086890FBFCF0DD +:1036E000A086486890FBFCF0E0868868B8F808106F +:1036F00090FBFCF0401A2087A4F84250A4F84450F4 +:103700000120FDF728FDB8F80400401EA8F80400C9 +:103710000420FDF7A3FE002871D0DFF8A081DFF8B8 +:1037200078C15C49B8F800200CF11C0C6439ACF18C +:10373000120A322A04D0E2B30020322A12D013E057 +:10374000A08EACF80000E08EACF80200208FACF840 +:103750000400B4F84230AAF80030B4F84430AAF8B3 +:103760000230E9E741F8205051F8203036F9107066 +:103770003B4441F8203026F8105004EB4003401C35 +:103780009D860328D9DB012A1AD14D484D4B05806F +:10379000012018804C4B02201870BCF80000A08655 +:1037A000BCF80200E086BCF804002087BAF80030BC +:1037B00000E008E0A4F84230BAF80200A4F844009F +:1037C000521EA8F8002041480288012A17D105801E +:1037D0000A68322092FBF0F2A2864A6892FBF0F26D +:1037E000E286896891FBF0F1B9F80800081A208791 +:1037F000A4F84250A4F844500120FDF7ACFC3088F6 +:10380000A18E401A30807088E18E401A7080B08896 +:10381000218F401AB080BDE8F08710B51D4C2648B6 +:10382000103C616888471A4890F8490020B1224945 +:103830000120FFF70AFF02E0A1681F488847BDE8A2 +:10384000104025E770B52248134C00682169411AE1 +:1038500056D420610F4DA0781035C0B1012857D043 +:1038600002285BD003284BD168698047A86980474C +:1038700005F0E0FC174905F009FB05F046FD4FF0A7 +:103880000052154B06F0C0FB0022144B28E038E034 +:103890002004002064080020500100208988883C12 +:1038A000000020411C0000203333534000F07F45CE +:1038B00047010020B000002064000020A00000208C +:1038C000A6000020A200002090000020A4000020FC +:1038D000B800002080E6C547965BC83F0000F03F77 +:1038E00005F0C4FB0022FB4B05F0C3FB05F0EEFC2A +:1038F000F94908600020A070A88821690844206167 +:1039000070BDA8688047A078401CA0702888F4E7A4 +:10391000E8688047A078401CA07070BD2869804787 +:10392000A078401CA0706888E7E72DE9F05FEB4DB8 +:10393000E888002869D0DFF8A8830024A3464FF464 +:103940007A79A8F10C06E888484507D104EB84028F +:1039500008EB820146F824B0C1F810B0E14F56F8E8 +:10396000241037F91400014446F8241005F062FCD5 +:10397000014604EB840208EB8200824600F0DAF98B +:1039800027F814B0D84F27F814B0E888012836D1AA +:10399000DAF81000012809DD401E05F04BFCDAF8CA +:1039A0000C200146104605F071FA00E0002007F0F7 +:1039B00008F98246CD4890F86800A8B105F043FCAC +:1039C000514605F0D1FC0FD2C549A5F80690C8F8BC +:1039D00010B0C1F824B0C1F838B0C6F808B0C6F8C5 +:1039E00004B0C6F800B00AE056F82410012291FB9A +:1039F000F9F027F814000F210A20FEF7E5FD641CFA +:103A0000032CA0DBE888401EE880B44C0020B64DB3 +:103A1000B44A223435F8103032F81010C91A0BB2FB +:103A200022F8103034F91010A1F54876B34201DACB +:103A3000314604E001F548718B4200DC194622F85A +:103A4000101024F81010401C0328E3DBBDE8F09FA1 +:103A500010B5A34CA3484C3461688847A34890F83C +:103A6000460020B19F490020FFF7EFFD02E0A1686A +:103A70009C488847BDE8104057E72DE9F04F85B0D6 +:103A80006020029040F2FE20039040F2C920049092 +:103A9000002797483D46009002F033FA8F4C0020F3 +:103AA0003434DFF850A220606060DFF84CB2A060D0 +:103AB0004CE07F1C029802F03FFA642003F05AF8B1 +:103AC00000F066F90A2003F055F88C4EB6F90000B4 +:103AD00005F0B0FB8046039805F0B5FB414605F0C4 +:103AE000D5F920F00049B6F9020005F0A3FB06461F +:103AF000049805F0A8FB3146019005F0C7F920F0C5 +:103B000000464146019805F0C1F97A4920F0004885 +:103B1000C94309EB01007A49884217D2564515DDA1 +:103B20005E4513DAD04511DDD8450FDA6D1C4946E4 +:103B3000206805F01DF920603146606805F018F92D +:103B400060604146A06805F013F9A060142F02D20E +:103B5000052DAED301E0052D1BD3284605F073FBE0 +:103B600005462068009905F05BF9294605F08EF9B5 +:103B700020606068009905F053F9294605F086F940 +:103B80006060A068009905F04BF9294605F07EF9C0 +:103B900003E04FF07E5020606060A06002F0E2F928 +:103BA0004E490120487005B0BDE8F08F2DE9F0477F +:103BB00054484A4D00686969411A74D4524908440E +:103BC000686100F0E5F84D4CB4F9000005F032FBF7 +:103BD00005F13406316805F023F905F04AFB00B21F +:103BE00020808246B4F9020005F024FB716805F0DC +:103BF00017F905F03EFB00B260808146B4F904007D +:103C000005F018FBB16805F00BF905F032FBDFF8A1 +:103C1000FC800FFA80FCA4F804C098F80E0000267F +:103C2000324905F12802931D80B16869A86100201E +:103C300001EB40077E8734F8107022F8107023F8EB +:103C40001070401C0328F3D388F80E60687858B1D0 +:103C50004F8FAAEB070020808F8FA9EB07006080B1 +:103C6000C88FACEB0000A080A86900281BD06F694A +:103C7000381A274FB84217D22648016881F0080148 +:103C80000160002034F9101032F91050A94201DA15 +:103C900022F8101033F91050A94201DD23F810105A +:103CA000401C0328EED3B6E50020AE6132F9104087 +:103CB00033F910502C4401EB400504EBD47444F369 +:103CC0004F04401C6C870328F0D3BDE8F047012067 +:103CD000FDF741BA1AE950413C0000205001002094 +:103CE000180800205E00002076000020200400203C +:103CF00059021B3F3333333F6666A63F70000020F6 +:103D000032337300B8000020A0860100B007002005 +:103D100080C3C9010C0C014010B5012003F0A7FBC2 +:103D20000820FDF775FB1F490020088010BD1D48C5 +:103D300003F0F0BB2DE9F041044600690D46401C3C +:103D40002061012820D005F075FA26680746314623 +:103D5000284605F05FF88046394605F097F8314669 +:103D600005F006F8064601466060284605F052F860 +:103D70000146404605F054F8A16804F0F9FF2660BA +:103D8000E060A060BDE8F081656000202560F8E794 +:103D900010B5054802F0F8F8BDE8104002490220CD +:103DA00053E400007C0000207000002070B5F94C46 +:103DB0000546C0B2A07003F082F8E079A1784840CF +:103DC000E071C5F30720A07003F079F8E079A178DD +:103DD0004840E071C5F30740A07003F070F8E07947 +:103DE000A1784840E071280EA07003F068F8E079EF +:103DF000A1784840E07170BD70B5E64C0546C0B290 +:103E0000E07003F05CF8E079E1784840E071C5F3D8 +:103E10000720E07003F053F8E079E1784840E07162 +:103E200070BD10B5044603F04AF8DA48C179614024 +:103E3000C17110BDD74AD848117A405C491C117233 +:103E4000704700B5FFF7F6FF0346FFF7F3FF03EBFC +:103E5000002080B200BD10B5FFF7F3FF0446FFF766 +:103E6000F0FF04EB004010BD70B504460D46242061 +:103E7000FFF7D7FF4D20FFF7D4FF0CB1212000E062 +:103E80003E20FFF7CEFFC34C0020E0712846FFF72D +:103E9000C8FF607ABDE87040C3E701460020E3E751 +:103EA00001460120E0E7BB48C079BAE710B50446F7 +:103EB00003E000BFFFF7B5FF641C20780028F9D1AC +:103EC00010BD02F04FBF2DE9F05FB248B34DDFF8EF +:103ED000D092407AB34EDFF8D0A2DFF8D0B2B44F20 +:103EE000DFF8D082B44C742877D00DDCA0F16400E8 +:103EF00010282DD2DFE800F09CABFDFCFBFAF9F8AE +:103F0000F7F6F5F4F3F2F1F0CD2867D010DCC9280C +:103F100039D006DC75287DD076287CD0C82817D10A +:103F20001CE0CA2849D0CB2859D0CC2810D161E058 +:103F3000EF2820D006DCCE286ED0CF2817D0D0288E +:103F400006D11EE2F02868D0FA2867D0FE2866D095 +:103F50000020FFF7A5FFBDE8F05FA4E70024454679 +:103F6000FFF76FFF25F81400641C082CF8D300201D +:103F7000FFF793FFEFE7FFF764FF42346080FFF73E +:103F800060FF2080F3E7FFF755FFE872FFF752FF6D +:103F900089F80000FFF75FFF3060FFF75CFF70609B +:103FA000FFF74FFFAAF80000FFF74BFFABF8000048 +:103FB000387840F002003870D9E70023FFF73AFF65 +:103FC000E518A873FFF736FF2876FFF733FF5B1C71 +:103FD00085F822000A2BF1D3C9E795E1D5E1002548 +:103FE000FFF72FFF04EB45016D1CA1F86A000F2DB0 +:103FF000F6D3BCE7FFF71EFF04F82C0FFFF71AFFFC +:104000006070FFF717FF2071FFF714FF6071FFF773 +:1040100011FF05E07DE195E1BCE1C2E1BDE1CBE14D +:10402000A071FFF707FFA070FFF704FFE0709EE7A5 +:104030000720FFF732FFD320FFF7F3FE6079FFF789 +:10404000F0FE0020FFF7EDFE4FF0004061E00A2097 +:10405000FFF723FF5948008800B2FFF7CDFE02F0BA +:10406000D1F900B2FFF7C8FE0120FDF7C9F90446F7 +:104070000220FDF7C5F944EA40040420FDF7C0F929 +:1040800044EA80041020FDF7BBF944EAC00408208C +:10409000FDF7B6F944EA0010FFF7AEFEE87829799B +:1040A0006A7940EA4100A979890041EAC2010843DE +:1040B000697840EA81114248027941EA0211427965 +:1040C00041EA4211EA7941EAC2112A7A41EA02211F +:1040D0006A7A41EA82210DE028E122E105E1F1E07E +:1040E000D8E0CFE0C8E0AFE09DE083E074E043E0DB +:1040F00034E011E0AA7A41EA4221C27A41EAC221BF +:10410000027B41EA0231427B807B41EA423141EA53 +:104110008030FFF74BFE1EE71220FFF7BEFE294D51 +:10412000002400BF35F91400FFF766FE641C032C61 +:10413000F8D3254D002400BF35F91400FFF75CFECD +:10414000641C032CF8D3214D002400BF35F9140062 +:10415000FFF752FE641C032CF8D3FCE61020FFF797 +:104160009CFE1B4D002400BF35F91400FFF744FEF0 +:10417000641C082CF8D3EEE61020FFF78EFE154DD8 +:10418000002400BF35F91400FFF736FE641C082C2C +:10419000F8D3E0E69401002090080020B00700204A +:1041A00099000020180100204C0100204E01002041 +:1041B0004201002030010020200400209A0000204D +:1041C000E20700206A0000204C0000207000002060 +:1041D00080000020780600201020FFF75EFE0024FB +:1041E0004FEA080535F91400FFF706FE641C082C99 +:1041F000F8D3B0E60E20FFF750FEE87AFFF711FE85 +:1042000099F80000FFF70DFE3068FFF7CFFD7068EA +:10421000FFF7CCFDBAF8000000B2FFF7EDFDBBF8E8 +:10422000000000B225E00520FFF737FEA448008813 +:1042300000B2FFF7E1FDA348B0F90000FFF7DCFD95 +:10424000387800F0010094E00820FFF726FE9E4D2C +:10425000002400BF35F91400FFF7CEFD641C022CCA +:10426000F8D39A48B0F90000FFF7C6FD9848B0F9B6 +:104270000000FFF7C1FD6EE60420FFF70EFE954833 +:10428000006846E70320FFF708FE93480078FFF731 +:10429000C8FD49E00720FFF700FE14F82C0FFFF7D8 +:1042A000C0FD6078FFF7BDFD2079FFF7BAFD6079AA +:1042B000FFF7B7FDA079FFF7B4FDA078FFF7B1FDD8 +:1042C000E07856E01E20FFF7E8FD00256619B07B78 +:1042D000FFF7A7FD307EFFF7A4FD96F82200FFF759 +:1042E000A0FD6D1C0A2DF1D335E61E20FFF7D5FD8C +:1042F0005FF0000504EB4500B0F96A00FFF77CFDB4 +:104300006D1C0F2DF6D326E66D20FFF7C6FD734812 +:1043100004E02F20FFF7C1FD70486E30FFF7C6FDA7 +:1043200019E60220FFF7B9FD0020A2E70820FFF7F9 +:10433000B4FD0024601CC0B2FFF773FD641C082CA0 +:10434000F8D308E6FFF776FD04460C20FFF7A5FD3D +:1043500094B1102C8FD11020FFF763FD604C2068C2 +:10436000FFF724FD6068FFF721FD0020FFF744FD03 +:104370000020FFF756FDEEE50020FFF752FD594CF7 +:10438000EDE70120FDF717F8F1E557494FF4C87044 +:104390000880ECE50120A873E9E50020FCF7DBFECE +:1043A000E5E50420FFF779FD4234B4F90200FFF798 +:1043B00023FDB4F900005CE70820FFF76EFD4B4DCC +:1043C000002400BF35F91400FFF716FD641C042C0F +:1043D000F8D3C0E570B5464C0025607810B3BDE851 +:1043E0007040FCF78DBC00BF02F05CFDA17951B1BB +:1043F00001291CD002291FD0032923D004292CD045 +:10440000052942D12FE0242803D00021A17149B908 +:1044100001E00121FAE7232802D0522835D102E039 +:10442000FCF76EFC31E0012002F04AFC2DE04D2843 +:1044300004D10220A07128E03C2801D00020F9E737 +:104440000320F7E740281FD8607125712572E071BD +:104450000420A0710120207017E06072E1794140D2 +:10446000E1710520E6E721796279914207D2E2798C +:104470004240E2711F4A5054491C217105E0E17924 +:10448000814201D1FFF71FFDA57102F0F5FC002864 +:10449000AAD16078002811D102F0EEFC00280DD1DD +:1044A0004FF40060FCF7DAFF002807D0124840788C +:1044B000002803D0BDE8704001F07BB970BD00005A +:1044C000480100204A010020200000209001002027 +:1044D000AA000020400000209800002068B90008D1 +:1044E00028010020200100205401002006010020A6 +:1044F0009401002090080020B007002070B5044609 +:10450000FE4D09E002F05BFD95F8EE00012802D1B6 +:10451000042002F02FFB641C20780028F2D100BF99 +:1045200002F05FFD0028FBD0BDE870401E2002F0C5 +:1045300021BB44F25061884201DDA0EB4100F0490B +:10454000884202DA48F6A041084470472DE9F04756 +:1045500006465068994614460D46301A04F06AFE25 +:10456000296804F093FC2061A768394604F052FCE6 +:104570008046E24890F8F60004F065FEE14904F058 +:104580004FFC01464FF07E5004F080FC2D68294618 +:1045900004F0EEFB0146284604F078FC414604F0A6 +:1045A0003FFC394604F0E4FB2061C4E901600146A8 +:1045B000D9F8080004F034FCBDE8F04704F059BE17 +:1045C00070B51D4614460E4604F034FE696804F0CA +:1045D00027FC316804F024FC216804F0C9FB014683 +:1045E0002060E86880F0004004F0C8FE03D2E8686C +:1045F00080F0004007E0E968206804F0BFFE01D2C7 +:10460000E86800E020682060BDE8704004F031BE3A +:1046100070B5BD4CD4E90D01401AFFF78AFF0028A0 +:10462000D4E90D01A0EB010002DDFFF782FF02E0FB +:10463000FFF77FFF404241F2941188422ADAD4E921 +:104640000D01401A04F0F6FDB04904F0E9FB0646FE +:10465000E06B04F0F8FD0546304606F0C5F9294642 +:1046600004F0DEFB04F005FE00B2A9492082884276 +:1046700002DB4942884200DD0846616B084448F687 +:10468000A0416064884200DD401A002800DA084436 +:10469000606470BD606BFBE72DE9F04F87B00646A4 +:1046A000FFF7B6FF984842F22831406C081A04F030 +:1046B000C1FD964904F0B4FB044605F0E3FB059008 +:1046C000204606F091F9904D049000243035DFF833 +:1046D00040A2DFF84092DFF840B2304604F0AAFD75 +:1046E000019089481A3030F9140004F0A3FD064601 +:1046F00004A850F82410019804F092FB314604F00D +:1047000089FB04F0B6FD00B2844925F81400884204 +:1047100002DB4942884200DD08467E4925F8140044 +:10472000603900F0CFFD04EB84067A4B76490746EA +:1047300009EB860835F91400603B42462831FFF743 +:104740003FFF744B7049074435F91400603B424603 +:104750002831FFF7FBFE384400B22BF81400504517 +:1047600001DA504604E040F6B832904200DD1046CF +:104770002BF81400674859F826102838641C40F8B4 +:104780002610022CADDB07B0BDE8F08F2DE9F05FFD +:104790005D4E0024DFF87C915036DFF87CB1A6F145 +:1047A000360AA9F1280900BF5A4956F82400803971 +:1047B00000F088FD3AF81410534F401A303755492D +:1047C00000B227F81400703900F07CFD054637F977 +:1047D000140056F8241004EB8407084409EB870101 +:1047E00088460A464B4B4849703B2831FFF7E8FEA4 +:1047F0002844484B44492BF814005D4656F82400E1 +:10480000703B42462831FFF7A1FE4549884202DB52 +:104810004942884200DD08463AF9141031316229D4 +:1048200000D8002035F81410084400B2384925F8A3 +:104830001400884202DB4942884200DD084625F820 +:104840001400344859F82710641C40F82710022C33 +:10485000AADBBDE8F09F70B50546086819681446E4 +:10486000401A04F0E7FC2849C96A04F0D9FA04F0B8 +:1048700000FD014624485030416029682268891AA9 +:10488000016070BD2DE9F0410F46DDE90685116834 +:1048900000681E46081A04F0CDFC044630683968EA +:1048A000401A04F0C7FC1849C96A04F0B9FA064670 +:1048B000014604F0B5FA07462146084604F0B0FA6E +:1048C000394604F055FA06F07CF9164904F0A8FAC6 +:1048D00004F0E8FCC8F8000084F00040314605F020 +:1048E000A7F9114904F09CFA104904F041FA04F0C8 +:1048F000C0FC286000281FDA1AE000002004002015 +:10490000B0B9FFFFDB0FC940A0010020D302373947 +:1049100048F4FFFF60090020E000002018FCFFFFC2 +:1049200030F8FFFF2C7D8E3FA00CB34500A00C4655 +:1049300048F6A04108442860BDE8F0812DE9F04721 +:10494000FD48FC4CD0E90056617804F14809B1B348 +:104950004FF07E50A16A04F099FA8246D9F804001B +:10496000301A04F067FCE16A04F05AFA514604F088 +:1049700057FA04F07EFC07B2D9F8000004F11A08D7 +:10498000281A04F057FC514604F04AFA04F071FC6E +:1049900002B204F12400B0F90210394401EBD171E4 +:1049A00041F34F01A8F80210B0F900301A4402EBAD +:1049B000D27242F34F02A8F8002041800280012009 +:1049C0006070C9E90056BDE8F08710B5044604F0F0 +:1049D00031FC002C01DC80F00040D84904F056FA8C +:1049E000D74904F01DFA05F04DFAD249C86210BD4E +:1049F00010B5D44CE07A002811D0D34800780528AF +:104A00000DD3CD49D14A0868106049685160FFF75D +:104A1000DCFFCF48C749008888820120207310BD81 +:104A200070B5C448C74B0124857ACA490022022DBB +:104A300006D0032D14D0062D20D0122D43D12FE007 +:104A4000BD4D4E686E608E682E6009694FF47A75B0 +:104A500091FBF5F1C04D2980C17AD97244732AE0E7 +:104A60004C79E40702D00979032903D00021C172EF +:104A700011B120E00121FAE7DA721CE0CC7AE407F8 +:104A800002D08C7A032C03D00024C47214B102E04B +:104A90000124FAE7DA72AC4B91F82F1019700AE092 +:104AA000AE4D8B8A2B80896942F2107391FBF3F132 +:104AB000AB4B19808473417B837B194203D04273D3 +:104AC0008273012070BD002070BD2DE9F04199492D +:104AD00000240A4691F809E0D679157AD78A4FF072 +:104AE000010C2246BEF1090F59D2DFE80EF008058D +:104AF00010161E2637484E00622803D04A72B52889 +:104B000002D04CE0022038E081F809C047E00322DF +:104B10004A720873C871087241E004224A7232185E +:104B2000CA712A440A72887239E005224A72321820 +:104B3000CA712A440A72C88231E006234B723318C4 +:104B4000CB7107EB00202B4480B20B72C882B0F50A +:104B5000007F01D9CA824A720A8320E03218CA71E2 +:104B60002A440A720A8B402A01D27A4B9854521C6A +:104B700090B20883B84212D1072048720FE0082390 +:104B80004B7286420BD04A7209E04A72854206D1C6 +:104B9000744880F800C0FFF743FF00B101242046AD +:104BA000CAE670B5034600200246054611E02E2CE9 +:104BB00004D1521C00290FD054181D559C5C00EBE9 +:104BC00080004000A4F13006092E01D8303820447E +:104BD000521C9C5C002CEAD170BD2DE9F0410025EF +:104BE00080462E462F46044604F00AF8016800E08D +:104BF000641C2078085C2028FAD0404609E01DB1EA +:104C000005EB85025206150E10F8012B303D2A44A3 +:104C1000D5B2221A022AF2DC09E01EB106EB8602A6 +:104C20005206160E10F8012B303E3244D6B28442A2 +:104C3000F3D820782E280ED1641C002007EB8702C1 +:104C4000570022788B5C202B02D1303F1744641C24 +:104C5000401C0428F2DB44480621464307EBC7000A +:104C600000EB071006EB8000B0FBF1F03F494D432D +:104C700000EBC51060E62DE9F04700272D4C0546F6 +:104C80003E464FF00109242815D032482146E0382D +:104C9000C9782C2D13D02A2D11D022460D2D5279F2 +:104CA00047D00A2D45D00F2902D24554491CE17046 +:104CB000002A73D0ACE0A670E6702671A8E04654D6 +:104CC000A178B046324629B1A279012A21D0022A20 +:104CD0007CD093E0A2710178472907D1417850290F +:104CE00004D18178472902D0522909D086E0C178C1 +:104CF000472904D10079412801D184F806907DE04C +:104D0000C1784D297AD10079432877D10220A0714A +:104D100074E0094E02292BD003292DD0042932D06A +:104D2000052934D006293AD0072941D0092947D08E +:104D300064E07AE0A0010020180100208096184B62 +:104D400035FA8E3CB0070020990000202001002099 +:104D500090010020B00900204C0100204E010020ED +:104D6000440100204601002040420F002D31010087 +:104D7000F648FFF732FF04E0007853283ED1306850 +:104D8000404230603AE0F148FFF727FF04E0007846 +:104D9000572833D17068404270602FE035E00078CA +:104DA000302801D9012000E00020E949C87225E03F +:104DB0000021E648FFF7F5FEE64908701EE005E031 +:104DC0000021E248FFF7EDFEE34916E0072902D093 +:104DD00008290DD012E00121DC48FFF7E2FE41F284 +:104DE000184148434FF47A71B0FBF1F0DB4904E01D +:104DF0000121D648FFF7D5FED9490880A078401C8C +:104E0000A07084F803802A2D0CD02079684020718E +:104E1000A07910B1D34A82F800900FB1012800D0D8 +:104E20000020D0E584F80590F2E772B18046007862 +:104E300000F076FA050198F8010000F071FA2844B4 +:104E40002179C0B2884200D101276671E0E72DE9DF +:104E5000FF5FC549C0B24FF0000B91F8EE1019B1D9 +:104E6000012904D002297DD1FFF705FF01E0FFF7FA +:104E70002CFE002876D0BD480178012910D00121F0 +:104E80000170B348C17A00296CD0B249097805296C +:104E900068D38246407830B19AF80C1031B108E0FE +:104EA00080F800B0EDE78AF80CB002E008B1FFF737 +:104EB0009FFDAF4805218E460278AF4C521CB2FBD5 +:104EC000F1F301FB1322AB490270002091F900902D +:104ED000A74954F820306831A54D41F82030A74942 +:104EE000783593FBF1F145F82010A54D00EB8007D4 +:104EF0004D4303EBC51342F2107593FBF5F5AEB2CB +:104F00009B4D403525F81060904DB83505EB87076F +:104F1000974D57F822C0603555F8208047F8223069 +:104F2000A8EB0C0C634445F8203093FBFEF3944D42 +:104F30006D42694303EBC1118D4B7033B9F1010F21 +:104F400043F8201005D1B61EB6F5797F01D844F894 +:104F50002010401C0228BBDB01F0FEFD844D296AB5 +:104F6000401A00E073E004F06EF9864903F08EFF0A +:104F7000A86201F0F1FD2862A86A4FF07E518842D4 +:104F800000DB0846A86203A902A87F4BCDE9000117 +:104F90001A1F211D7848FFF775FC02996427B1FBA1 +:104FA000F7F27A4956460A80039A92FBF7F0784A5C +:104FB00010809AF80C0018B9A1F800B0A2F800B05F +:104FC000FFF7BCFC307A10B9F07900283FD068496F +:104FD000343101F1080000F11C06CDE90001331D58 +:104FE0003246211D6448FFF74DFC231D624A311DE6 +:104FF0003046FFF730FC5F4C94F90000012828D0C0 +:10500000022824D1584E0121B6F9FC0000F065F9C0 +:10501000FFF742FB96F8F8005E4A18B1696C91FB05 +:10502000F7F01080B6F8F400E96B88420BD2D5E9AE +:105030000D01401AFFF77DFA002800DC404242F2E1 +:105040001071884203DD01202070A88A1080BDE81D +:10505000FF9FFFF79BFBFAE72DE9F047424C123424 +:10506000207804F0F0F8DFF83091494603F00EFFA5 +:10507000364D10352860A07A04F0E5F8494603F073 +:1050800005FF464EEE606860607804F0DCF8444F3F +:10509000394603F0FBFE10352860E07A04F0D3F8BF +:1050A000494603F0F3FE6860607D04F0CCF8DFF859 +:1050B000D480414603F0EAFEC5E90206A07804F078 +:1050C000C2F8394603F0E2FE10352860207B04F078 +:1050D000BAF8494603F0DAFE6860A07D04F0B3F840 +:1050E000414603F0D3FEC5E902066CE42DE9F04722 +:1050F00007460024FFF7B0FF00222A49384601F096 +:1051000018FF194E96F8EE00012802D0022817D099 +:10511000D8B1DFF8948000254FF4964A08F11409BD +:1051200058F8250001F04AFF57450BD0B7F5164F48 +:105130003CD0B7F5614F4ED0B7F5E13F3BD14EE0E3 +:105140000424E6E759F8240033E03AE0D0080020D0 +:10515000B0070020990000204C0100204E010020E3 +:1051600044010020460100202004002042010020CC +:10517000A0010020910000201801002080969800D6 +:10518000D3CEFEFF00007A44240100204801002015 +:105190004A010020920100200000C8420000FA44A9 +:1051A000000020414F4E000808BA000809EB8400B7 +:1051B0004068FFF7A3F90A2001F0DCFC6D1C052D07 +:1051C000AEDB384601F0FAFE96F8EE0001280AD070 +:1051D000022814D019E009EB84008068E9E709EBA4 +:1051E0008400C068E5E7554D0024285D01F0E7FE26 +:1051F000042001F0BFFC641C8C2CF6D305E050A009 +:10520000FFF77CF95BA0FFF779F94FF47A7001F0B2 +:10521000B1FC5D480078002804D0BDE8F0471020BC +:10522000FCF7F6B8FDE52DE9F05FDFF86CA100248E +:10523000564FDFF85C81DFF85C9125460AF1280BB8 +:1052400027F8145028F8145004EB840629F8145059 +:105250000AEB860000F06DF80BEB860000F069F8B1 +:105260004D48503000EB860000F063F8641C022CBF +:10527000E6DBBDE8F09F7CB5484C02682260096817 +:1052800061600068FFF7A1FBA4F1240101F10800AF +:10529000434ECDE90001231D2246311D3046FFF764 +:1052A000F1FAA4F15805331D686B68643246211D7C +:1052B0002046FFF7D0FA686BA8633A48B0F8FA00C6 +:1052C00068827CBD10B50C4603F0B4FF216803F082 +:1052D000A7FDBDE8104003F0CCBF70B52F4C583C83 +:1052E000E26B21B1B0EB520F0BD3500809E09042B2 +:1052F00000D310462B4900B2B1F8FA10814200DB0E +:105300000846B4F9125000B2A84208DD2649A06A46 +:1053100003F086FD03F0ADFF284400B2608270BD4B +:105320003038C0B2092801D9C01FC0B200F00F0048 +:105330007047002101604160816070473CBA0008FD +:1053400024504D544B3331342C302C312C302C31F3 +:105350002C302C302C302C302C302C302C302C306D +:105360002C302C302C302C302C302C302C302A325D +:10537000380D0A0024504D544B3232302C3230302C +:105380002A32430D0A00000046010020C40000201C +:10539000E4000020E000002010090020F8010020B7 +:1053A00018010020200400200000C84270B5374CCE +:1053B00001260546667001F0BAFBA168421AC4E9ED +:1053C000020241F288300021824200D9A170304AA5 +:1053D000A07815540F2802D0401CA07070BD2D4835 +:1053E0002670018070BD2C48032190F89720274833 +:1053F00012B1C170072101E00222C27001710122C5 +:1054000026494FF4E13001F094BD20480078704700 +:10541000F0B51E4A1E4C11781C3CE1B192F804C054 +:10542000D6781B4B03215F1817F8015CF54005F097 +:105430000F05072D09D213F801E017F8017C07EAE0 +:105440000C070EEB072744F82570891CC9B21029F8 +:10545000E9D300211170104907280ED2527862B1A9 +:10546000084491F8972090F88C004AB154F8200035 +:105470004FF4777101EB500006E0B1F89800F0BDF1 +:1054800034F8200000F5777080B2F0BD20020020D3 +:105490000C0A00209C00002020040020AD530008CE +:1054A0002DE9F0417E4C0746012520782E0380B976 +:1054B00001F052FBA1683231884207D37948257048 +:1054C000066001F049FBA060BDE8F081207800286B +:1054D000FAD001F041FBA16839448842F4D300209E +:1054E00020707048001F066001F036FBA0606E4817 +:1054F000017809B1491E01706570E5E7F8B5684D9E +:105500008DF800008DF801108DF802208DF8033021 +:10551000A8791DF8001044292FD04C292BD04D29F3 +:1055200027D04E292CD032240026032806D274B16D +:105530002046FFF7B5FFA879032808D301F00CFB3C +:10554000A968001B884202D95748AE710670687876 +:10555000012801D0002C0BD1A879032801D2401CCE +:10556000A87150496E70091F2E704FF4805008606A +:10557000F8BD6424D8E7C824D6E74FF4FA64D3E72B +:105580000024D1E72DE9F047DFF820A10546444C7F +:105590009AF80B004FF00109002610B184F8029030 +:1055A00000E0A6704FF40070FBF758FF404F18B3AF +:1055B000404941484FF0020C91F89F30B0F900008B +:1055C00003EB830282420FDA97F80180B8F1000FF3 +:1055D0000AD084F8049091F8A010194401EB8101DD +:1055E000814201DA84F804C0824203DA797809B989 +:1055F00084F804C000B926711020FBF701FF40B108 +:105600009AF8071011B99AF8080008B1F87AA8B109 +:10561000E6702079022814D0012817D0E0780128FC +:1056200017D0A078012817D0042D19D0022D1ED034 +:10563000012D1ED0607901281ED022E084F803904D +:10564000E7E74E22442311464C200DE04D234C2227 +:1056500008E04D234E2201E04D235322532102E066 +:1056600044234D224D215320BDE8F04746E7442313 +:1056700005E044234E22F5E7787810B14E234D2201 +:10568000ECE70948007818B1BDE8F047322007E799 +:1056900004492670091F4FF480500860BDE8F08768 +:1056A000300200201408014090000020E207002092 +:1056B000B0070020200400209C00002010B55E28C8 +:1056C00002D05D2805D008E05D2001F0F8FB3E2007 +:1056D00003E05D2001F0F3FB3D20BDE8104001F048 +:1056E000EEBB2DE9F041132000F020F9994C206821 +:1056F000002800DC4042984D90FBF5F000B200F02D +:105700001FF91B2000F012F92068002800DC40423D +:105710000A2690FBF6F042F2107790FBF7F107FBB8 +:10572000110000B200F00CF9232000F0FFF820680F +:10573000002801DA532000E04E2000F001F9122089 +:1057400000F0F4F86068002800DC404290FBF5F0BF +:1057500000B200F0F5F81A2000F0E8F860680028C0 +:1057600000DC404290FBF6F090FBF7F107FB1100E4 +:1057700000B200F0E5F8222000F0D8F860680028B8 +:1057800001DA572000E04520BDE8F04100F0D8B82C +:1057900070B5724D04462878844209D014B14FF494 +:1057A000165002E06E48D0F80001FEF78AFB2C701C +:1057B00070BD2DE9F04701F0CFF9684D6968401AD6 +:1057C0007D287DD301F0C8F968606878654F401C7A +:1057D000DFF89481DFF894916870002404F12400CC +:1057E000C0B200F0A3F8388803F02DFD064638F962 +:1057F000140003F01FFD314603F048FB494603F057 +:105800000FFB03F036FD00B200F09AF8641C032C85 +:10581000E4DB5E2001F053FB68784FF064048007FE +:1058200025D1102000F082F8514E306890FBF4F042 +:1058300000B200F085F8212000F078F8306890FB85 +:10584000F4F104FB110000B200F07AF8142000F02B +:105850006DF84848B0F9000000F072F81C2000F024 +:1058600065F8002000F06CF85E2001F028FB6878F5 +:10587000400734D1022000F059F83F484FF00A08A1 +:10588000B0F9001091FBF8F000B200F059F80220D6 +:10589000FBF7E4FDD0B139486E210078484315216B +:1058A000B0FBF1F63A2000F041F8B6FBF4F738B25D +:1058B00000F046F83B2000F039F804FB176000E0E8 +:1058C00032E0401DB0FBF8F000F03AF81020FBF792 +:1058D00097FD08B1FFF705FF5E2001F0F0FA687848 +:1058E000282821D10020687001F036F94FF47A7130 +:1058F000B0FBF1F43C25B4FBF5F6B6FBF5F005FB87 +:105900001067172000F012F8380200B200F018F803 +:10591000182000F00BF805FB164000F011F8BDE868 +:10592000F0475E2001F0CBBABDE8F08710B5044621 +:105930005E2001F0C4FA2046BDE8104001F0BFBA75 +:1059400010B50446C0B2FFF7B9FEC4F30720BDE8A6 +:105950001040B3E618010020A08601003C020020A0 +:1059600020040020580100206A00002000007A4432 +:105970004000002090010020AC0000209800002092 +:105980002DE9F0410646007890B008B1012500E00D +:105990000025DFF8D880404602F054F934480090E2 +:1059A00000243448CDE90104012725B10220CDE9C6 +:1059B0000304802002E0CDE90374002005904FF439 +:1059C0008070069080000790202008900002CDE9AA +:1059D00009046946404602F0A2F90121404602F05E +:1059E000BBF98DF830500B948DF831704FF4602076 +:1059F000CDE90D040DB1022000E001201C4C8DF812 +:105A00003C004C3C0BA9204602F088F803230122FD +:105A10000421204602F0D7F82DB131780323022269 +:105A2000204602F0D0F80121204602F0A0F8012122 +:105A3000204602F092F8204602F0A3F8204602F039 +:105A4000A5F80028FAD1204602F0A7F8204602F077 +:105A5000A9F80028FAD10121204602F0AAF810B0D6 +:105A6000BDE8F081034931F810007047080002409A +:105A70004C2401404402002070472DE9FC47DFF828 +:105A80004891054699F80000C0B30027B8463E4645 +:105A90003C46641CE4B26B4608223221532000F0DD +:105AA00073FC9DF800009DF80110202C00EB0120F4 +:105AB00000B207449DF802009DF8031000EB01209E +:105AC00001B288449DF804009DF8051000EB012008 +:105AD00000B206449DF8070000F07F0001D20028C4 +:105AE000D7D197FBF4F0288098FBF4F0688096FB00 +:105AF000F4F0A88089F80140BDE8FC87FFE76B4619 +:105B000006223221532000F03FFC9DF800009DF852 +:105B1000011000EB012028809DF802009DF8031081 +:105B200000EB012068809DF804009DF8051000EB53 +:105B30000120A880E0E7244810B500784FF0080263 +:105B400000284FF02D014FF053000ED000F016FC4E +:105B50000A223121532000F011FC0C222C21532069 +:105B600000F00CFC9022382108E000F007FC0A222B +:105B70003121532000F002FC0A222C21532000F096 +:105B8000FDFB124940F20910088010BD38B50546EA +:105B900000200C468DF8000001466B460122532080 +:105BA00000F0F2FB18B19DF80000E52801D00020BC +:105BB00038BD0549287808700548206005486060B0 +:105BC0000548A060012038BD48020020580100208F +:105BD000375B00087B5A0008795A000810B54FF46B +:105BE0008044204602F012F9012805D1204602F037 +:105BF0001BF9B1490120087010BD30B4AE4AAF485E +:105C000091884389B0F91440C91A03895943C913CB +:105C1000B0F912300C44DB0293FBF4F31944C16178 +:105C2000906830BC00F0C7B838B5A34C207810B9E4 +:105C30006088401C60806B460322F621772000F0CC +:105C4000A3FB9DF800009DF80110000440EA01202C +:105C50009DF8021008439949B1F92010C1F10801DB +:105C6000C840A06038BD9548342190F8200001EB71 +:105C700080109149C2B200200870F421772000F012 +:105C80007DBB38B58C4C207810B96088401C608092 +:105C90006B460222F621772000F076FBBDF800006B +:105CA00040BAA08038BD844900202E220870F4211B +:105CB000772000F063BB2DE9F043DFF8FC91044648 +:105CC00085B099F8010018B1012005B0BDE8F08356 +:105CD0004FF40055ADF80C5002208DF80E00102046 +:105CE000774E8DF80F0003A9304602F015FD6F00C6 +:105CF000ADF80C7004208DF80F0003A9304602F0B7 +:105D00000BFD35610E21022002F093FD00208DF87D +:105D1000080008208DF809004FF001080197474658 +:105D20008DF80A8001A802F03BF828208DF81000B9 +:105D30000F208DF811008DF812008DF8137004A853 +:105D400001F0B9FE142000F015FF6B460122D021AE +:105D5000772000F019FB594F9DF800000321F875DA +:105D60003984552802D075610020AEE76B460122C8 +:105D7000D121772000F008FB9DF8000000F00F0112 +:105D800039760009787600F05FF889F8018041F2F1 +:105D9000F810208046F29050608041F28830A08058 +:105DA0004848A0604848E060484820614848606131 +:105DB0004848A06188E770B54049CA69B1F90E400A +:105DC000A2F57A6202FB02F31D136C43E512B1F9EE +:105DD0000240B1F90460544305EBE424B1F90050EA +:105DE00004EB850591F82040A54056437213B1F9A4 +:105DF0000C601B135E4302EB2642921C9210C98872 +:105E000002F50042AD1C5143C90B4CF25032A0EBDD +:105E1000A500E2405043B0F1004F03D24000B0FB78 +:105E2000F1F002E0B0FBF1F040000112494340F60E +:105E3000DE325143284A0914424301EB224101F664 +:105E4000CF6100EB211070BD00B587B06B46162204 +:105E5000AA21772000F098FABDF8000041BA17484F +:105E60000180BDF8021049BA4180BDF8041049BA5A +:105E70008180BDF8061049BAC180BDF8081049BA42 +:105E80000181BDF80A1049BA4181BDF80C1049BA28 +:105E90008181BDF80E1049BAC181BDF8101049BA10 +:105EA0000182BDF8121049BA4182BDF8141049BAF6 +:105EB000818207B000BD00004C0200201C0A0020B7 +:105EC00000100140A75C0008835C0008675C0008C4 +:105ED000295C0008FB5B000843E3FFFF08B50020D6 +:105EE0008DF800006B4601220A211E2000F04CFABA +:105EF00018B19DF80000482801D0002008BD0120FD +:105F000008BD08B54FF48050ADF8000002208DF8B0 +:105F1000020004208DF803006946264802F0FCFBCD +:105F2000642000F027FE782200211E2000F026FACF +:105F3000322000F01FFE08BD10B504467922002172 +:105F40001E2000F01BFA322000F014FE2246012130 +:105F50001E2000F013FA01220221BDE810401E208D +:105F600000F00CBA10B5782200211E2000F006FACD +:105F7000202201211E2000F001FA00220221BDE8AA +:105F800010401E2000F0FAB91CB504466B460622EC +:105F900003211E2000F0F8F9BDF8000040BA20806F +:105FA000BDF8020040BA6080BDF8040040BAA0808D +:105FB0001CBD0000000C014030B587B005464FF411 +:105FC0004060ADF8140002208DF816001C208DF8FA +:105FD000170005A9FE4802F09FFBFE4CE56000F0AB +:105FE00014FAE06801F026FF684601F08EFF0022F7 +:105FF0004FF44071E06801F0BEFF0025ADF8045099 +:106000004BF6FF70ADF806004FF48040ADF80C0081 +:10601000F14800900121E06801F085FF6946E068E1 +:1060200001F01BFF4FF4A06001F040FD22208DF82D +:1060300010008DF811508DF8125001208DF81300CA +:1060400004A801F038FD21208DF810008DF81150C2 +:1060500004A801F030FD07B030BD70B5DD4CE0683C +:10606000858A15F4706F01D00121217015F4E06F5D +:1060700024D0018B00224FF4806101F07CFFA80541 +:106080001CD4E0680188890518D40188C9050CD59D +:106090000188C905FCD4012101F059FFE06801889D +:1060A0008905FCD4FFF788FF08E0012101F04FFFCC +:1060B00000224FF44071E06801F05DFFE068818AE2 +:1060C00021F4706181820020207170BDC5E72DE947 +:1060D000F041C04CE068818A4FF00105C9B2CA079F +:1060E0004FF0000627D0018821F4006101800121D2 +:1060F00001F037FFE670607A20B1607860B9A0796E +:10610000FF2809D061790022E06801F041FFA07901 +:10611000FF280FD0FF20B8E06570E079022804D195 +:10612000E068018841F40061018061790122E06842 +:1061300001F02EFFC9E08A074FF4806734D5BFF322 +:10614000508FE079012810D1607A70B1607860B129 +:106150000021E06801F005FFBFF3508FE068018B7C +:10616000012101F0F4FEA5701CE0E068008BBFF394 +:10617000508FE07902280DD1607A58B1607848B12B +:106180000021E06801F0EDFE93E03946E06801F09F +:10619000F2FE9AE0E079032804D1607A10B16078C9 +:1061A000002874D10122F0E74A0753D5A570627A1E +:1061B00088494978CAB3C9B3E17902291FD90021B6 +:1061C00001F0CFFEE06801F0E0FE94F9031062698F +:1061D0005054491CE1700121E06801F0B8FEA5703F +:1061E000E06801F0D2FE94F9031062695054491C32 +:1061F000E17001223946E06801F0BDFE25E0012191 +:1062000001F0A5FEE06801F0C0FE94F90310626998 +:106210005054491CE170E06801F0B7FE94F9031096 +:1062200062695054891CE1700FE000E000E009B998 +:10623000217A31B1012101F08AFEE078401CE07042 +:1062400003E0012101F079FE6570E0680188C9056D +:10625000FCD43AE04A061BD501F097FE94F90310EE +:1062600062695054491C48B2E070E179C01C814217 +:1062700004D100223946E06801F07DFEE17994F90D +:106280000300814221D100F10100E0701DE010E027 +:1062900009061AD594F903104B1C5AB20BD0236986 +:1062A000595CE27001F06FFEE07994F903108842C6 +:1062B0000BD1002269E7E270A17901F064FE607AF7 +:1062C0000028F6D1E0790028F3D094F90310E079A2 +:1062D000401C814209D16670A07828B100224FF499 +:1062E0004071E06801F047FE2671BDE8F081EEE6FE +:1062F000B3E6ECE67FB5374C400047F230556071AD +:10630000A1710126267200206072C4F810D0C4F872 +:1063100014D06946E27126712070102A02D900203B +:1063200004B070BD002003E01E5C0E54401CC0B2DF +:106330009042F9D3E068818889050ED40188C905A7 +:1063400005D401888905FCD4012101F0F6FD012264 +:106350004FF44071E06801F00EFE207910B16D1E1F +:10636000FBD104E01DB1207880F00100D8E76089FE +:10637000401C6081E068FFF71FFED0E707B502AB65 +:106380000122FFF7B7FF0EBD70B5124C4FEA400077 +:1063900047F230556071A1710020207201216172B5 +:1063A00063612361E27121712070E0688188890551 +:1063B00016D40188C90505D401888905FCD40121BA +:1063C00001F0BBFD01224FF44071E06806E00000DF +:1063D000000C014058020020801A060001F0CBFD9D +:1063E000207910B16D1EFBD104E01DB1207880F042 +:1063F000010070BD6089401C6081E068FFF7DCFD32 +:10640000002070BD2F48408970472DE9F8434FF4B4 +:106410004067ADF800704FF002088DF8028014203C +:10642000294C8DF803006946204602F075F939467B +:10643000204602F0D1F90025261502E00A2000F0DE +:106440008EFB3146204602F0C0F90028F6D03146D6 +:10645000204602F0C3F90A2000F081FB31462046B5 +:1064600002F0BAF90A2000F07AFB6D1CEDB2082D9B +:10647000E7D34FF400652946204602F0AFF90A2021 +:1064800000F06DFB3146204602F0A8F90A2000F02A +:1064900066FB3146204602F09FF90A2000F05FFBC0 +:1064A0002946204602F098F9ADF800708DF8028078 +:1064B0001C208DF803006946204602F02DF9BDE846 +:1064C000F883000058020020000C014038B5044653 +:1064D0006B4602221B216820FFF756FFBDF8000023 +:1064E00043F2903140BA08444FF48C71B0FBF1F0A4 +:1064F0002330208038BD81884942818070471CB597 +:1065000004466B4606221D216820FFF73DFFBDF8BB +:10651000000040BA00B2C11700EB917080102080DB +:10652000BDF8020040BA00B2C11700EB91708010B4 +:106530006080BDF8040040BA00B2C11700EB917052 +:106540008010A0801CBD10B5192000F013FB0022A4 +:1065500015216820FFF712FF10B9032000F08DFB12 +:1065600028481621007840F018026820FFF706FF3F +:10657000002217216820FFF701FF01223D2168203A +:10658000FFF7FCFE01223E21BDE810406820FFF726 +:10659000F5BE10B50446192000F0ECFA00221521D2 +:1065A0006820FFF7EBFE002808D017482060174846 +:1065B00060601748A0601748E060012010BD1149D5 +:1065C000622817D006DC0A281AD0142816D02A28E8 +:1065D00009D111E0BC2804D0B0F5807F03D10020A0 +:1065E00000E0012008700878162140F018026820A9 +:1065F000FFF7C4BE0220F5E70320F3E70420F1E72C +:106600000520EFE77002002047650008FF640008DE +:10661000F7640008CD6400083EB505460C466846A0 +:1066200001F071FFF848641EADF804400068F749B6 +:10663000B0FBF1F0401EADF800000020ADF8060000 +:10664000ADF802006946284601F028FD3EBD70B550 +:106650001646EF4B00EB800203EB8205ED4A02EB9E +:1066600000142068FFF7D8FFD4E90101002200F0F0 +:1066700040FA217B3246206800F0E0F9A07B18B197 +:106680000121206801F064FF0121206801F056FF1C +:10669000207B30B1042807D008280AD00C2806D166 +:1066A0000AE02068343001E020683830686028460D +:1066B00070BD20683C30F9E720684030F6E7F8B557 +:1066C00016460F46D24A00EB800102EB8105D14904 +:1066D00001EB00144FF6FF712068FFF79DFFD4E92E +:1066E0000101012200F005FA217B0022206800F060 +:1066F000E8F90121206801F021FF607B8DF800009E +:1067000000208DF8010001208DF802008DF80300B3 +:10671000684601F0D0F92F60AE72207B30B10428BA +:1067200008D008280DD00C2809D10EE00122022142 +:10673000206802E001220421206801F014FF2846AD +:10674000F8BD012208212068F7E701221021206806 +:10675000F3E770B5B04C0221204601F035FFAC4D97 +:10676000012814D01021204601F02EFF01281AD153 +:1067700009261021204601F033FF204601F021FFB9 +:10678000D5F8B42001463046BDE8704010470826D1 +:106790000221204601F024FF204601F00CFF0146B3 +:1067A000D5F8A020EFE770BD70B50C460646022173 +:1067B00001F00AFF964D012823D00421304601F054 +:1067C00003FF012826D00821304601F0FDFE0128F4 +:1067D0002AD01021304601F0F7FE01282ED1E41C0A +:1067E00064B21021304601F0FBFE304601F0E9FEB4 +:1067F00004EB84020146E0B255F82220BDE8704067 +:10680000104764B20221304601F0EAFE304601F042 +:10681000D2FEEDE7641C64B20421304601F0E0FED4 +:10682000304601F0CAFEE3E7A41C64B208213046FA +:1068300001F0D6FE304601F0C2FED9E770BD00215E +:106840004FF08040B0E704217448ADE70A21744856 +:10685000AAE7704A30B5083A00239088D08091802A +:10686000081A81B240F68C20814201D9D37030BD24 +:106870006848A1F2EF24083840F2DB55C078AC42FA +:1068800004D2082802D2674C24F81010401CD070A3 +:106890006548038030BD5E4A00EB800370B502EBB3 +:1068A00083025C4BD47A03EB001318681B7B84B122 +:1068B000D18194895B4D091B1182947A25F81410BB +:1068C0000024D4722246194600F0FBF85648048092 +:1068D00070BD91810121D172BDE87040022219463C +:1068E00000F0EFB82DE9F04704460020617901B1CE +:1068F0000220617801B1401C4649DFF81081E03187 +:10690000002551F82070A1F1E8064FF47A797A5DFC +:1069100002F00F0002F0F001FF2A5AD0A2781AB15B +:10692000022853D0032851D0A2790AB182424DD017 +:1069300011F0300F02D0227802B90021E27832B192 +:10694000627922B9082801D0092800D18021227952 +:106950002AB162791AB9021F032A00D88021CA0617 +:1069600005D500223149FFF7AAFE082008E08A0673 +:1069700008D5B2782E49FFF7A2FEB07800F10100E9 +:10698000B07023E04A0610D52289B8FBF2F189B233 +:106990004A46FFF75CFE0146224A3078103242F840 +:1069A000201000F10100307010E009060ED5628958 +:1069B000B8FBF2F189B24A46FFF749FE0146194A8F +:1069C0007078403242F82010401C70706D1C0E2D03 +:1069D0009DDB0020BDE8F0870E4A083A127890420D +:1069E00005D2104A103252F82000406801807047EA +:1069F000084A083A5278904205D20A4A403252F880 +:106A00002000406801807047BC03002040420F0016 +:106A1000400A00207C020020002C014000040040BD +:106A200000080040580B00209C000020536800081C +:106A3000976800083A4931F81000E4E77FB5064648 +:106A400015460C46684601F067FD7020ADF8000061 +:106A50000120ADF802000020ADF804000220ADF8DE +:106A60000800C001ADF80650ADF80C0074B1042C5C +:106A700015D0082C1CD00C2C07D16946304601F0EB +:106A8000F1FB0821304601F08CFD7FBD69463046A0 +:106A900001F03DFB0821304601F06DFD7FBD6946E8 +:106AA000304601F069FB0821304601F06AFD7FBDE8 +:106AB0006946304601F09CFB0821304601F06BFD31 +:106AC0007FBDFEB5064614460D46684601F02EFD14 +:106AD0000120ADF804000021ADF80050ADF806101B +:106AE000ADF80810ADF802406946304601F06EFC82 +:106AF000FEBDF8B5064615460C46684601F05DFE3B +:106B0000ADF800400DB1282000E018208DF80300FA +:106B100002208DF802006946304601F0FDFDF8BD07 +:106B2000580B00206B484168491C4160704710B504 +:106B300068494FF0E02348689A694C68A042FAD14E +:106B40006549891A4822B1FBF2F100EB4002C2EB21 +:106B5000C01001EBC00010BD5E484068704730B502 +:106B60000546FFF7E4FF0446FFF7E1FF001BA842DC +:106B7000FAD330BD30B504464FF47A7502E02846AA +:106B8000FFF7EDFF641EFAD230BD2DE9F0418CB065 +:106B90001822524901A802F060F8032700F0A2FE73 +:106BA00001214F4801F059FA012144F61D2001F05E +:106BB0004BFA0121084601F03EFA01F060FA4FF667 +:106BC000FF70ADF8000000268DF803606946454867 +:106BD00001F0A2FD6946444801F09EFD6946434824 +:106BE00001F09AFD0121424801F0FAFD002401ADB7 +:106BF0004FF0020805EBC4008188ADF800108DF855 +:106C0000028080798DF8030055F83400694601F060 +:106C100083FD641CBC42EDD3334808211030016071 +:106C2000102101602F4980141031086007A801F07D +:106C3000BDF930490798B0FBF1F0264908602E48AD +:106C40004FF47A710068B0FBF1F0B0F1807F0BD2A5 +:106C500020F07F414FF0E020491E4161274AF0219A +:106C600011708661072101612548FFF7A5F96420AD +:106C7000FFF780FF0CB0BDE8F0811B4A10211432F1 +:106C800011600821121F1160044640F2DB10154FFD +:106C9000151F44434E021437A7F1040C286880F0F6 +:106CA00010002860286880F008002860A01EFFF708 +:106CB00061FF3E601920FFF75DFFCCF80060EDE753 +:106CC00010B111490F4808600C4910481739086085 +:106CD000704700006C0300204019010000BB000851 +:106CE0000700400000080140000C01400010014076 +:106CF0000002300040420F00BC03002023ED00E002 +:106D000000580040EFBEADDEF04F00200400FA0551 +:106D1000CD48CC4A81685318CC4A1365C3688B426E +:106D200003D9591A9164836004E0C1F580719164BC +:106D300000218160C5480121443001F00DB810B533 +:106D40004FF4005001F01EF8C0480021443001F01B +:106D500003F8BD48083003C8814202D0BDE81040A6 +:106D6000D6E710BD2DE9F04192B004464FF4007013 +:106D7000ADF83C0002208DF83E001820B44D8DF88F +:106D80003F000FA9284601F0C7FC2815ADF83C00CC +:106D900048208DF83F000FA9284601F0BDFC0E20C9 +:106DA0008DF8400001218DF841108DF842108DF8CA +:106DB000431010A800F07FFE0B940024ADF834407F +:106DC0000C20DFF89082ADF83040ADF83600ADF819 +:106DD0003240ADF838400BA9404601F009FC9B4F0A +:106DE0005837384600F02EFFA81408F10405009526 +:106DF000CDE909049848CDE9010480260494CDE941 +:106E00000564A81503902020CDE90740694638465F +:106E100000F085FF0121384600F09EFF012240214D +:106E2000404601F06AFC384600F0A9FF8649874FCA +:106E300044374860384600F005FF10200290009566 +:106E40000494CDE90564079469463846089400F037 +:106E500066FF01220221384600F089FF7B488464E6 +:106E600001228021404601F048FC0121404601F00A +:106E700022FC12B0BDE8F081744810B5583000F023 +:106E80007EFF71494968884201D0012010BD002071 +:106E900010BD6D48D0E90210814201D10120704738 +:106EA0000020704768496C4B4A68C2F58070185CD6 +:106EB000521E4A6002D14FF480724A607047624AA3 +:106EC000604BD1685854491CC8B2D0605F48406CD0 +:106ED000C00700D11CE7704710B5044602E0641CEF +:106EE000FFF7EDFF20780028F9D110BD1FB504464B +:106EF000684601F0D5FB00205349ADF8040000942A +:106F0000ADF80600ADF80800097809B1002100E0ED +:106F1000082141F00401514CADF80A10ADF80C0005 +:106F20006946204601F064FB0121204601F0C3FBC5 +:106F30001FBD2DE9FC410F4680460121144648043F +:106F400001F08BF8404D262002262C708DF80400AD +:106F500001208DF805008DF806608DF8070001A866 +:106F600000F0A9FD0420ADF800008DF802601820A3 +:106F7000374E8DF803001CB96946304601F0CCFB52 +:106F80000820ADF8000048208DF80300694630461F +:106F900001F0C2FB4046FFF7A9FF304E012240F24C +:106FA0002551304601F091FB2CB9012240F22771A6 +:106FB000304601F08AFB2F61BDE8FC8196E722494B +:106FC0000A78002A0CD1264B8A699854521C02F088 +:106FD0007F008861012240F22771204801F075BBD3 +:106FE00070471948D0E90510814201D1012070474E +:106FF0000020704770B5194E358840F22550124C6C +:10700000054206D0206920B1304601F07EFB21699F +:10701000884728060CD5D4E90510814209D01048CC +:10702000405C0E4A121D1080491C01F07F00606117 +:1070300070BD3046BDE87040002240F2277101F07B +:1070400044BB0000B80C0020740300200000024084 +:107050000008014000380140B80B00200044004007 +:10706000B80D0020FEB5384C0125207878B10128F4 +:1070700023D0022820D164208DF8000033488DF8F9 +:10708000015000264078A8B38DF8025044E07A20E1 +:107090008DF800002E486B460222B0F90000FF2157 +:1070A000C0F1B40000EBD070C0F347008DF80100D0 +:1070B0006D20FFF71FF92570FEBD264979208DF858 +:1070C0000000B1F900000A2290FBF2F010F15A031F +:1070D00001D5002003E05A30B42800DDB4208DF83B +:1070E0000100B1F9020090FBF2F010F15A0102D553 +:1070F000002004E00EE05A30B42800DDB4208DF802 +:1071000002006B460322FF216D20FFF7F3F80220F7 +:107110002070FEBD8DF802606B460322FF216D20BA +:10712000FFF7E8F82670FEBD08B56B208DF800006B +:107130000A208DF801008DF802006B460322FF2122 +:107140006D20FFF7D7F808BD90030020B00700209E +:1071500090010020200000208188494281807047F2 +:107160001CB504466B46062243216820FFF70CF944 +:10717000BDF8000040BA00B2C11700EB917080105A +:107180002080BDF8020040BA00B2C11700EB917038 +:1071900080106080BDF8040040BA00B2C11700EB57 +:1071A00091708010A0801CBD08B54FF40050ADF860 +:1071B000000002208DF8020004208DF803006946CB +:1071C000494801F0A9FA80226B216820FFF7D6F820 +:1071D0000520FFF7CFFC002219216820FFF7CEF829 +:1071E00003226B216820FFF7C9F8022237216820AB +:1071F000FFF7C4F803221A216820FFF7BFF818220E +:107200001B216820FFF7BAF83848007814280BD003 +:10721000152809D0542807D0552805D010221C2144 +:107220006820FFF7ABF808BD0822F8E7018842881C +:1072300002804942418070471CB504466B460622D5 +:107240003B216820FFF7A0F8BDF8000040BA00B26B +:10725000C11700EB5170C0102080BDF8020040BA89 +:1072600000B2C11700EB5170C0106080BDF804007F +:1072700040BA00B2C11700EB5170C010A0801CBD15 +:107280001B4940F2FF3008807047F8B505461646A6 +:107290000C462320FFF76EFC6B4601227521682007 +:1072A000FFF772F8002804D09DF80000682801D08C +:1072B0000020F8BD1EB10D495520087005E00B4BAC +:1072C00001220C216820FFF75FF80A4828600A486D +:1072D00068600A48A8600A4820600A4860600A4856 +:1072E000A0600120F8BD0000000C014091030020C7 +:1072F0005801002081720008397200082D720008C0 +:10730000A97100086171000859710008018849429B +:10731000018041884942418070471CB504466B4654 +:10732000062201211C20FFF72FF8BDF8000040BA0B +:1073300040F38D00C11700EB917080102080BDF8E4 +:10734000020040BA40F38D00C11700EB917080102D +:107350006080BDF8040040BA40F38D00C11700EB17 +:1073600091708010A0801CBD08B52020ADF80000F1 +:1073700002208DF8020004208DF80300694627489A +:1073800001F0CAF900222A211C20FEF7F7FF022291 +:107390000E211C20FEF7F2FF03220F211C20FEF716 +:1073A000EDFF12222B211C20FEF7E8FF02222C21E8 +:1073B0001C20FEF7E3FF01222D211C20FEF7DEFF3B +:1073C00000222E211C20FEF7D9FF05222A211C2095 +:1073D000FEF7D4FF12494FF48070088008BD38B51D +:1073E000044600208DF800006B4601220D211C2070 +:1073F000FEF7CAFF28B19DF800002A2803D01A28FA +:1074000001D0002038BD0749216007496160074964 +:10741000A16007490870012038BD00000008014044 +:1074200058010020697300081B7300080D730008E1 +:107430009203002010B5444C4448A18801F0C5F9DE +:1074400018B1FFF774FBA0600AE0FFF770FBA168BA +:10745000884205D9401A3B2190FBF1F06169088010 +:10746000E068BDE8104000F0DFBCE3E7E2E7FEB50E +:107470000125354C022110B1012810D109E04FF44B +:10748000807060804000A080E0600920207017209C +:1074900004E06580A180E16025700720607060884D +:1074A000ADF8000010268DF80360284F8DF802100B +:1074B0006946384601F030F9A088ADF80000042094 +:1074C0008DF803006946384601F026F9217801203D +:1074D00001F0AFF9E06800F0A7FCE068019000203F +:1074E0008DF808008DF809608DF80A5001A800F0A9 +:1074F00057FC94F9010000F01F018D4040094FF046 +:10750000E02101EB8000C0F80051FFF725FB3C387B +:107510002061FEBD70B50546FFF71EFB0A4C2169D0 +:107520003C3188420FD3C4E90405084D61882846E0 +:1075300001F052F90B20FFF712FB61882846BDE8E5 +:10754000704001F04BB970BD94030020000C014065 +:1075500001884942018081884942818070471CB579 +:1075600004466B460622A8216820FEF70DFFBDF8F1 +:10757000000040BA00B2C11700EB9170801060802B +:10758000BDF8020040BA00B2C11700EB9170801044 +:107590002080BDF8040040BA00B2C11700EB917022 +:1075A0008010A0801CBD10B56420FFF7E3FAF02224 +:1075B00023216820FEF7E2FE10B90320FFF75DFBF0 +:1075C0000520FFF7D7FA1E4820210078BDE81040BB +:1075D00040F00F026820FEF7D1BE38B504461920EE +:1075E000FFF7C8FA6B4601220F216820FEF7CCFE98 +:1075F0009DF80000D32801D0002038BD114820603C +:10760000114860601148A060012038BD0C49202855 +:1076100006D0362806D04E280DD05D2804D10CE0C7 +:10762000002000E0402008700878202140F00F0280 +:107630006820FEF7A3BE8020F5E7C020F3E7000036 +:10764000AC030020A77500085F750008517500089D +:107650002DE9F04FDFF868829A480023B8F80A1045 +:107660004068B8F80850A0EB0121A5FB017C03FBA2 +:1076700001CCB8F804004FEAE17905FB09C506041E +:10768000FC0944EA456416EB040E43EBE51AB8F82E +:107690000650B8F80240A5FB017C03FB01CC4FEA81 +:1076A000C43605FB09C54FEA172444EA056416EB06 +:1076B000040BB8F80C601846A6FB017C00FB01C166 +:1076C00006FB09114FEA412444EAD75140EB252536 +:1076D0004FF4FA6409191A46B1F5FA6F15DAA1F5F3 +:1076E000FA62524302EB82025310774C9210A1428D +:1076F0000BDA01F2DC514943C1EBC104234401EB35 +:10770000410404EBC10102EB6102DE17BEEB03038F +:107710006C4C6AEB0601D617BBEB0202A46865EB62 +:107720000605A4FB026700FB027004FB0500720D56 +:1077300042EAC0224015D21A60EB0100410441EA3E +:10774000D230BDE8F08F10B500F071F85D49886067 +:1077500010BD5C48012200784030C1B27720FEF7AE +:107760000DBE10B500F063F85649486010BD55488D +:10777000012200785030C1B27720FEF7FFBD2DE91D +:10778000FE4305464FF40054ADF8004002208DF84A +:10779000020010204D4E8DF803006946304600F07F +:1077A000BBFF74610A20FFF7E5F902AB0122A021BB +:1077B0007720FEF7E9FD002824D001221E21772042 +:1077C000FEF7DCFD4FF42F60FFF7C9F90024DFF866 +:1077D000F0802646A02700BF07EB4400C1B201ABF2 +:1077E000022277200196FEF7CFFDBDF8040040BAD3 +:1077F00028F81400641C082CEEDB314800F029F84E +:1078000010B10020BDE8FE8342F21070288068802D +:107810004FF47A60A8802E48A8602E48E8602E4871 +:1078200028612E4868612E48A8610120EAE708B562 +:107830006B46032200217720FEF7A6FD9DF800008D +:107840009DF80110000440EA01209DF80210084351 +:1078500008BDF0B5C289002102F47F4502F00F0493 +:107860000123C5814FEA010230F8126006B10023FE +:10787000521C082AF8DB4FF0FF36F3B90022D30779 +:1078800022F0010302D0C35C594002E0C35A81EAEE +:10789000132108230F0401D581F4C05149005B1E58 +:1078A000002BF7DC521C102AE9DB2543C581C1F30C +:1078B0000330844201D10020F0BD3046F0BD00000D +:1078C000380E0020B003002024FAFFFF0010014012 +:1078D0006F77000863770008537700084777000840 +:1078E00051760008694910B54868694A10F00C03E0 +:1078F000684803D0042B01D0082B0BD002604968E4 +:10790000644AC1F30311121D515C026822FA01F2AC +:10791000026010BD4A684B6802F470124FF0020416 +:1079200013F4803F04EB924202D04B689B0301D5D5 +:10793000594B00E0564B5A43E0E7544810B40268F4 +:10794000002142F4803202604FF4A063026801F12A +:10795000010112F4003F01D19942F7D101688A0375 +:107960004E4931D50A6842F010020A600A6822F0D6 +:1079700003020A600A6842F002020A60416841603C +:1079800041684160416841F480614160416821F48F +:107990007C114160416841F4E8114160016841F0A7 +:1079A0008071016001688901FCD5416821F0030103 +:1079B0004160416841F0020141604168C1F38101C9 +:1079C0000229FAD110BC7047026842F0010202603D +:1079D0000022046802F1010214F0020F01D19A4260 +:1079E000F7D102689207EDD50A6842F010020A60EA +:1079F0000A6822F003020A600A6842F002020A6082 +:107A00004168416041684160416841F48061416082 +:107A1000416821F47C114160416841F4601141608A +:107A2000016841F08071016001688901FCD54168FD +:107A300021F003014160416841F002014160416869 +:107A4000C1F381010229FAD110BC4BE70F4810B5F0 +:107A5000016841F0010101604168114A1140416033 +:107A60000168104A11400160016821F48021016021 +:107A7000416821F4FE0141604FF41F018160FFF76E +:107A80005CFF09494FF00060086010BD0010024023 +:107A900000127A00BC03002000093D0000200240D3 +:107AA0000000FFF8FFFFF6FE08ED00E0184908436C +:107AB000184908607047F0B50F21C4780278012397 +:107AC0004FF0E026DCB1134C2468457804F4E06400 +:107AD000C4F5E064240AC4F10407E1408478BD40A1 +:107AE0000C402C4321010C4C1155007800F01F0173 +:107AF0008B40400906EB8000C0F80031F0BD02F079 +:107B00001F008340500906EB8000C0F88031F0BDB3 +:107B10000000FA050CED00E000E400E010B542685A +:107B2000464B0C791A400B6842EA04221343436027 +:107B30008368434A1340D1E9024222434C7943EA25 +:107B400044031A438260C26A097C22F47002491E0F +:107B5000C9B242EA0151C16210BD0029816802D058 +:107B600041F0010101E021F001018160704700292D +:107B7000816802D041F4807101E021F4807181605C +:107B80007047816841F0080181607047014600201C +:107B90008968090700D501207047816841F0040118 +:107BA00081607047014600208968490700D501209F +:107BB00070470029816802D041F4A00101E021F45E +:107BC000A0018160704770B5072509290AD9C468EA +:107BD000A1F10A0606EB4606B540AC43B3401C4390 +:107BE000C46007E0046901EB4106B540AC43B34013 +:107BF0001C4304611F23072A09D2446B521E02EB67 +:107C0000820293409C4391400C43446370BD0D2A13 +:107C100009D2046BD21F02EB820293409C43914035 +:107C20000C43046370BDC46A0D3A02EB82029340B8 +:107C30009C4391400C43C46270BD0000FFFEF0FF06 +:107C4000FDF7F1FF01684FF6FE721140016000215F +:107C5000016041608160C1604F494F4A08399042DC +:107C600003D1486840F00F0006E04B4A14329042BE +:107C700004D1486840F0F00048607047464A283216 +:107C8000904203D1486840F47060F5E7424A3C32C4 +:107C9000904203D1486840F47040EDE73E4A5032CC +:107CA000904203D1486840F47020E5E73A4A6432D4 +:107CB000904203D1486840F47000DDE7364A7832DC +:107CC000904203D1486840F07060D5E7334A111FF5 +:107CD000904203D1086840F00F0006E02F4A1432AA +:107CE000904204D1086840F0F000086070472B4AC9 +:107CF0002832904203D1086840F47060F5E7274AC3 +:107D00003C32904203D1086840F47040EDE7234ACA +:107D100050329042EAD1086840F47020E5E730B56F +:107D2000036847F6F07293430C6A8A682243D1E9EC +:107D300004452C4322438C692243CC6922434C6A7C +:107D400022438C6A22431A430260CA6842600A686E +:107D500082604968C16030BD0029016802D041F0ED +:107D6000010102E04FF6FE72114001607047002AE7 +:107D7000026801D00A4300E08A430260704740680D +:107D800080B27047C10003D50449091F08607047DD +:107D90000149083948607047080002400804024061 +:107DA00030B523498379026853B30B6893430B6062 +:107DB0000A1D13680468A343136002790A44136818 +:107DC0000468234313601A4A083213680468A34303 +:107DD0001360131D1C680568AC431C604479102CAB +:107DE00005D021440A68006802430A6030BD11686A +:107DF000046821431160196800680143196030BDAF +:107E00000079084401689143016030BD084A014689 +:107E100000201268064B0A4014331B680B4202D044 +:107E2000002A00D0012070470149143108607047D2 +:107E3000000401405A4910B588424FF0010101D1B8 +:107E40004C0501E04FF48004204600F00FF9204675 +:107E5000BDE81040002100F009B970B504468088E3 +:107E600086B00D4620F03F06684600F09FF84D4969 +:107E70000298B0FBF1F189B20E43A680228822F06D +:107E800001022280484B2A689A421CD85200B0FB5B +:107E9000F2F080B2042800D20420491C2184A0837F +:107EA000208840F00100208021884FF6F530014005 +:107EB000A8886A89104308432080A8892989084333 +:107EC000208106B070BDEB88A3F53F46FF3E05D18B +:107ED00002EB4202B0FBF2F080B208E002EBC20318 +:107EE00003EB0212B0FBF2F080B240F480400205D6 +:107EF00001D140F001004FF4967251434FF47A7271 +:107F0000B1FBF2F140F40040C7E741F28831016073 +:107F1000002181804BF6FF72C280018141814FF4C4 +:107F20008041818170470029018802D041F0010120 +:107F300001E021F00101018070470029018802D091 +:107F400041F4807101E021F48071018070470029C3 +:107F5000018802D041F4007101E021F40071018038 +:107F600070470029018802D041F4806101E021F4CA +:107F7000806101807047002A828801D00A4300E0B6 +:107F80008A438280704701827047008AC0B270477E +:107F900012B141F0010101E001F0FE0101827047E0 +:107FA0000054004040420F00A0860100374A10B53F +:107FB000516811F00C03364903D0042B01D0082B73 +:107FC00026D001605168334B01F0F00109095C5C77 +:107FD0000168E1404160546804F4E064240A1C5DD7 +:107FE00021FA04F48460546804F460544FEAD42401 +:107FF0001B5D21FA03F1C1605268264B02F4404236 +:108000004FEA92321B1F9A5CB1FBF2F1016110BD85 +:108010005168536801F470114FF0020413F4803F6B +:1080200004EB914102D053689B0301D51A4B00E049 +:10803000174B5943C5E7154A0029516901D001433F +:1080400000E0814351617047104A0029916901D0D5 +:10805000014300E08143916170470C4A0029D169D6 +:1080600001D0014300E08143D1617047074A0029F4 +:10807000116901D0014300E0814311617047034859 +:10808000416A41F080714162704700000010024077 +:1080900000127A00D403002000093D0030B50288A8 +:1080A000FD4BFE4C98420DD0A0420BD0B0F1804F5A +:1080B00008D0FB4DA84205D0FA4DA84202D0FA4D97 +:1080C000A84203D122F070054A882A43F74DA842FE +:1080D00006D0F74DA84203D022F44075CA882A433F +:1080E00002808A8882850A88028598420AD0A04246 +:1080F00008D0F04A904205D0EF4A904202D0EF4AB1 +:10810000904201D1097A01860121818230BD30B5CA +:10811000028C22F001020284028C8388048B22F0FC +:10812000020224F073050C882C430D8915434A88FC +:108130002A43D94DA8420BD0D84DA84208D0DD4DD6 +:10814000A84205D0DC4DA84202D0DC4DA8420DD19A +:1081500022F008054A8923F440732A4322F00405DB +:108160008A882A438D891D43CB892B4383800483CE +:10817000C9888186028430BD70B5028C22F010025D +:108180000284028C8488038B0D8823F4E6464FF624 +:10819000FF7303EA052535430E8922F0200203EA26 +:1081A000061616434A8803EA02123243BA4EB04218 +:1081B00002D0BA4EB04215D122F080064A8924F48A +:1081C000406403EA0212324322F040068A8803EA3E +:1081D000021232438E8903EA86062643CC8903EADB +:1081E0008404344384800583C9880187028470BD78 +:1081F00070B5028C22F480720284028C8488838B96 +:108200000D8823F073031D4322F400730E894FF68B +:10821000FF7202EA06261E434B8802EA0323334319 +:108220009D4EB04202D09D4EB04215D123F400665F +:108230004B8924F4405402EA0323334323F4806639 +:108240008B8802EA032333438E8902EA061626430B +:10825000CC8902EA0414344384808583C9888187E9 +:10826000038470BD70B5028C22F480520284048CA9 +:108270008288838B0D8823F4E6464FF6FF7303EA6A +:108280000525354324F400560C8903EA04343443AD +:108290004E8803EA063626437F4CA04202D07F4C2C +:1082A000A04205D122F480448A8903EA8212224343 +:1082B00082808583C988A0F84010068470BD828BB7 +:1082C00022F440628283828B4FF6FF7303EA01211E +:1082D0000A4382837047828B22F00C028283828B56 +:1082E0000A4382837047028B22F440620283028B2E +:1082F0004FF6FF7303EA01210A4302837047F0B58A +:10830000048C24F010040484078B048C4FF6FF7552 +:1083100027F4734705EA03333B4305EA02221A4375 +:108320005D4B05EA011698420ED05C4B98420BD08B +:10833000B0F1804F08D05A4B984205D0594B984223 +:1083400002D0594B984205D124F02001314341F02D +:10835000100104E024F0A0030B4343F0100102835A +:108360000184F0BD028B22F00C020283028B0A43CF +:108370000283704770B5048C24F001040484058BDB +:10838000048C4FF6FF7606EA0313134325F0F3053A +:10839000414A2B4390420ED0404A90420BD0B0F15C +:1083A000804F08D03E4A904205D03E4A904202D0CB +:1083B0003D4A904202D124F0020201E024F00A0278 +:1083C0000A4342F001010383018470BD2DE9F05F8F +:1083D0000D4604460888304FDFF8C0C0DFF8C08083 +:1083E0004988AA882B894FF0804960B3042832D08D +:1083F0004FF6FF7E082836D0208C9B4620F4805014 +:108400002084A38B268C704600EA022223F4734357 +:108410001A4300EA0B3010430EEA013EBC420BD077 +:10842000644509D04C4507D0444505D01D4A9442C7 +:1084300002D01D4B9C425AD126F4005141EA0E0154 +:1084400041F4805158E02046FFF794FFE988204628 +:10845000BDE8F05F86E72046FFF751FFE988204638 +:10846000BDE8F05F3FE7208C20F480702084B4F8F2 +:108470001CA0208C0EEA031313432AF0F30A0EEA21 +:10848000012B43EA0A03BC4220D064451ED04C4570 +:108490001CD044451AD013E0002C014000340140A8 +:1084A0000004004000080040000C004000100040A4 +:1084B00000140040004001400044014000480140D9 +:1084C000494A944202D0494A944204D120F40070AF +:1084D00040EA0B0002E020F42060084340F4807082 +:1084E000A3832084E9882046BDE8F05FF3E626F404 +:1084F00002420A4342F48051A08320462184E98845 +:10850000BDE8F05FDBE64FF6FF718180002101805E +:10851000C1804180017270470021018041808180CB +:10852000C180018141818181C18170470021018029 +:10853000418001228280C180018170470029018829 +:1085400002D041F0010101E021F0010101807047FA +:10855000002930F8441F02D041F4004101E0C1F38A +:108560000E0101807047002A828901D00A4300E091 +:108570008A4382817047028B22F008020A430283F9 +:108580007047028B4FF6FF7322F4006203EA012169 +:10859000114301837047828B22F008020A438283D1 +:1085A0007047828B4FF6FF7322F4006203EA0121C9 +:1085B000114381837047808E7047008F7047808F92 +:1085C0007047B0F84000704702460020138A928935 +:1085D0000B4202EA010202D0002A00D001207047BB +:1085E000C94301827047000000080040000C0040B1 +:1085F00030B50446008A85B00D464CF6FF71084040 +:10860000E98801432182A1894EF6F3100140A88830 +:108610002A8910436A890A431043A081A08A4FF631 +:10862000FF410840A9890143A1826846FFF7BEFCCB +:108630003848844201D1039800E00298A1890904D6 +:10864000002900EBC00101EB0010296802DA4FEAB3 +:10865000410101E04FEA8101B0FBF1F06422B0FB7F +:10866000F2F14FEA01114FEA11136FF018056B4355 +:1086700000EB8300A3891D044FF0320306D503EB02 +:10868000C000B0FBF2F000F0070005E003EB0010C3 +:10869000B0FBF2F000F00F000843208105B030BDC0 +:1086A0004FF41651016000218180C18001810C22AC +:1086B0004281818170470029818902D041F40051B3 +:1086C00001E021F400518181704710B5C1F34213DC +:1086D00001F01F040121A140012B07D0022B07D07C +:1086E0001430002A026805D00A4304E00C30F8E791 +:1086F0001030F6E78A43026010BD002A828A01D05A +:108700000A4300E08A43828270478088C0F30800F1 +:108710007047000000380140F0B5CA78002502F02B +:108720000F03D20601D58A7813430A784FF00F0E53 +:1087300012F0FF0F4FF001021CD004680F8802FAFC +:1087400005F63740B74211D14FEA850C0EFA0CF707 +:1087500024EA070703FA0CF43C43CF78282F02D011 +:10876000482F02D002E0466100E006616D1C082D32 +:10877000E4D304600C88FF2C1ED944685FF0000627 +:1087800006F1080702FA07F50F882F40AF420FD114 +:108790004FEA860C0EFA0CF7BC4303FA0CF73C4385 +:1087A000CF78282F00D14561CF78482F00D10561BF +:1087B000761C082EE4D34460F0BD4FF6FF710180B3 +:1087C000022181700421C170704702460020926826 +:1087D0000A4200D001207047016170474161704733 +:1087E000F0B51C4C002801DAE36900E06368420D33 +:1087F000120185B2C0F301579540C0F30346032F21 +:1088000005D0C2020AD50322B240934307E023F009 +:108810007062636823F07063636002E0AB4343F00F +:10882000706201B12A43002801DAE261F0BD6260A2 +:10883000F0BD10B58A0721F003040649130F214447 +:108840000F228C689A4094438C608A689840024357 +:108850008A6010BD00000140374836494160374901 +:10886000416070473448016941F0800101617047FF +:1088700031490420CA68D20701D001207047CA6874 +:10888000520701D502207047C968C906FBD50320ED +:10889000704700B50346FFF7EBFF02E0FFF7E8FF84 +:1088A0005B1E012803D0002B00D1052000BD002B4A +:1088B000F4D1FAE770B505464FF430263046FFF79D +:1088C000E8FF042811D11C4C206940F0020020610F +:1088D0006561206940F0400020613046FFF7D9FF14 +:1088E000216941F6FD721140216170BDF0B5054668 +:1088F0004FF4005C0E466046FFF7CBFF042814D10E +:108900000D4C206940F0010020612E806046FFF789 +:10891000C0FF41F6FE77042804D1300C6880604621 +:10892000FFF7B7FF216939402161F0BD0249C860F6 +:10893000704700002301674500200240AB89EFCD5E +:1089400014481549026800608A4203D013488047E2 +:1089500013480047134E4FF0090030601248016879 +:1089600021F07061016041020160104C182020600C +:108970000F49104808601048D0F800D04068004700 +:10898000FEE7FEE7FEE7FEE7FEE7FEE7FEE7FEE7BF +:10899000FEE7FEE7F04F0020EFBEADDE4D7A0008A7 +:1089A000ED0000081810024004000140140C0140C2 +:1089B000000C01404434434400F0FF1FF0B5002692 +:1089C000012400E04C43B0FBF4F58D42FAD217E0ED +:1089D000B0FBF4F504FB1500B4FBF1F41EB9002D57 +:1089E00001DC002CF4D10A2D01DA302704E00AB1B1 +:1089F000412700E061270A3F3D4403F8015B761CF4 +:108A0000002CE5D100201870F0BDF0B5002601243F +:108A100000E04C43B0FBF4F58D42FAD218E000BF01 +:108A2000B0FBF4F504FB1500B4FBF1F41EB9002D06 +:108A300001DC002CF4D10A2D01DA302704E00AB160 +:108A4000412700E061270A3F3D4403F8015B761CA3 +:108A5000002CE5D100201870F0BD2DE9F04115463D +:108A6000069C0E4680460BB1302700E020272046AA +:108A700000E06D1E10F8011B29B1002DF9DC02E0A9 +:108A800039464046B047281EA5F10105F8DC01E053 +:108A90004046B04714F8011B0029F9D1BDE8F08128 +:108AA0002DE9FF5F994614468A4683462D2701AE7D +:108AB00082E025297DD14FF0000814F8011B4246C1 +:108AC0004546302903D114F8011B4FF00108A1F1EC +:108AD0003000092818D80A23002505E0984213DC45 +:108AE00005FB030514F8011BA1F13000092809D981 +:108AF0003138052801D80A3004E0A1F141000528E9 +:108B000002D80A300028E9DA6C2902D114F8011BD6 +:108B1000012264291DD008DC002952D0252948D023 +:108B200058292CD0632947D141E073294BD07529AE +:108B300002D0782940D122E059F8040B01AB92B958 +:108B40001AE0434600962A4651465846FFF785FFED +:108B500032E059F8040B01AB42B1002803DA40427D +:108B60008DF804705B1C00220A2110E0002803DA53 +:108B700040428DF804705B1C00220A2112E059F873 +:108B8000040B52B1582905D0002201AB1021FFF788 +:108B900015FFD6E70122F8E70BE0582905D000229F +:108BA00001AB1021FFF731FFCBE70122F8E719F8FD +:108BB000041B58465246904714F8011B00297FF4C5 +:108BC00078AFBDE8FF9F59F8041B00230091BAE776 +:108BD0000A4AC2E9001070470FB4084810B5D0E93E +:108BE000001003AB029AFFF75BFF00BFFEF751F9DD +:108BF0000028FBD010BC5DF814FB0000E40300204B +:108C00000048704724BC0008A0F16101192900D870 +:108C1000203870472DE9F05F994615460F46834688 +:108C20004FF0FF36DDF828A011E0A819441009FB29 +:108C3000047080460146584652469047002802D0AC +:108C400004DA254603E04046BDE8F09F2646A5EB42 +:108C500006000128E9DC0020F6E740EA01039B0753 +:108C600003D009E008C9121F08C0042AFAD203E0A1 +:108C700011F8013B00F8013B521EF9D27047D2B205 +:108C800001E000F8012B491EFBD270470022F6E7F5 +:108C900010B513460A4604461946FFF7F0FF204672 +:108CA00010BD034600E0401C0278002AFBD111F8F9 +:108CB000012B00F8012B002AF9D11846704730B576 +:108CC0000EE003460A4601E05B1C521C1C78157836 +:108CD000AC4201D1002CF7D115F0FF0F04D0401C9D +:108CE0000278002AEDD1002030BD10B5044604E022 +:108CF0000B7800F8013B03B1491C521EF8D2204604 +:108D000010BDCAB20178914203D009B1401CF9E705 +:108D1000002070470146002000E0401C0A5C002A49 +:108D2000FBD170472DE9F0410546002090460E46E4 +:108D3000044600E0641C44450BD2285D00F059FB5A +:108D40000746305D00F055FB381A02D1295D002935 +:108D5000F0D1BDE8F08170B5064600F0ABFD0468C7 +:108D600005460A220021304600F049FB2C6070BD08 +:108D7000F0B480EA0102D40F4200B2EB410F02D2FC +:108D80000246084611464A0042D0C30DDDB2C1F387 +:108D9000C752AD1A202D35DAC1F3160141F4000295 +:108DA00004B15242C5F1200602FA06F12A411044EC +:108DB000B3EBD05F23D0C4B1012DA0EBC35009DCCD +:108DC000F0BC4FF0004202EAC35200F50000DBB2F3 +:108DD00000F056BB400000F1807000EBC350A0F1E2 +:108DE000807040EAD170490009E0490841EAC07149 +:108DF000A0EBC35000F50000400800EBC350F0BCEE +:108E000000F035BB6142012202EB4101001BF6E795 +:108E1000F0BC704781F00041AAE780F00040A7E76E +:108E200080EA010210B502F00043400026D04A005B +:108E300023D04FEA106101EB1261C0F35600C2F378 +:108E4000560240F4000042F40002A0FB0220A1F10F +:108E50007F014FEA0040140401D000F1010050EA04 +:108E6000124001D44000491EC2B20C0604EBD010DF +:108E7000401C4008802A02D003E0002010BD20F0F2 +:108E80000100002900DA0020184310BD30B480EA48 +:108E9000010202F0004530F0004221F0004015D000 +:108EA000A0B1C0F3C753C2F3C754C2F31601C0F355 +:108EB0001600E41A41F4000140F400027D349142AE +:108EC00001D3641C00E04900002C02DA30BC002011 +:108ED00070474FF400000023914201D3891A0343E5 +:108EE00040084FEA4101F7D151B1914202D14FF010 +:108EF000004105E002D24FF0010101E06FF00101F5 +:108F000003EBC450284430BC00F0B1BA420005D095 +:108F1000C0F3C7525242914201DC0020704700EB7F +:108F2000C15070472DE9FE4F804681EA0300C00F13 +:108F30000C46009021F0004123F00045B8EB020000 +:108F4000A94105D24046214690461C460B460246A2 +:108F500023F00040104304D14046214603B0BDE851 +:108F6000F08F270DC7F30A00C3F30A510290401A8D +:108F70000190402866DAC3F3130040F4801B009888 +:108F8000924620B10023D2EB030A63EB0B0B01984E +:108F90005946C0F14002504600F0FAF906460D4627 +:108FA00050465946019A00F012FA10EB0800614150 +:108FB000002487EA115284EAE7731A433BD0009AEF +:108FC0003AB3019A012A4FEA075210DC001B61EB09 +:108FD00002014FF0004202EA0752CDE90042001CB4 +:108FE00041F5801132462B4600F0D1FAB6E7001B5E +:108FF00061EB0201001C41F5801300185B41201851 +:10900000A2F5001747EB030140EAD570B6196D4190 +:1090100011E06D084FEA360645EAC0754FEA07527F +:10902000001B61EB0201001C41F5801149084FEA69 +:1090300030000019514132462B4603B0BDE8F04FD5 +:1090400000F098BA0098012240000023D0EB020201 +:1090500063EBE073009821464FEAE074B8EB000040 +:1090600061EB0401E9E783F000435BE781F0004135 +:1090700058E72DE9FE4F81EA030404F0004421F093 +:10908000004100944FF0000B23F0004350EA01042C +:1090900002D052EA030404D10020014603B0BDE827 +:1090A000F08FC3F30A54C1F30A552C44A4F2F334ED +:1090B0000194A0FB0254C1F3130141F48011C3F3E6 +:1090C000130343F4801301FB024400FB034E840AA4 +:1090D000970A44EA815447EA8357A4FB076802953C +:1090E0008D0A05FB07854FEA932C04FB0C542705DA +:1090F000029D4FEA065847EA1637B5EB08056EEBB6 +:10910000070C870E920E47EA811742EA8312A7FBEB +:109110000201B6EB0B0164EB00042B0D43EA0C33A8 +:109120005E1844EB1C50DA465146E7FB0201C5F3DA +:1091300013044FEA0B3343EA14534FEA0432019C01 +:1091400043EA0603A4F10C040294009CCDE900B4A8 +:1091500000F01DFAA2E72DE9F04D81EA030404F0C6 +:10916000004B21F0004514464FF0000A23F0004167 +:1091700050EA050220D054EA01021DD0C5F30A5777 +:109180000246C5F31303C1F31300C1F30A5640F4BA +:10919000801543F48013A7EB0608101BD64608F28F +:1091A000FD3873EB050002D308F1010801E09218C5 +:1091B0005B41B8F1000F03DA00200146BDE8F08DF5 +:1091C00000204FF48011064684460EE0171B73EB17 +:1091D000050705D3121B63EB050306434CEA010C9C +:1091E00049084FEA300092185B4150EA0107EDD17F +:1091F00052EA030012D082EA040083EA0501084320 +:1092000003D100224FF0004308E0101BAB4102D213 +:109210000122002302E06FF0010253101AEB060056 +:109220004CEB085110EB0A0041EB0B01BDE8F04D8F +:1092300000F0A0B9C10F80EAE0700844CA07962385 +:10924000002100F01DB996230022114600F018B944 +:109250000EB5C10F80EAE0700844CA07002140F251 +:1092600033438DE80E000A460B4600F090F903B038 +:1092700000BD00F0004220F00040C10DC0F3160018 +:1092800040F400007F2901DA00207047962903DCB2 +:10929000C1F19601C84001E096398840002AF4D017 +:1092A0004042704720F00040C10DC0F3160040F46A +:1092B00000007F2901DA00207047962903DCC1F104 +:1092C0009601C840704796398840704770B5C1F321 +:1092D0000A5201F000450024C1F3130140F2FF33AC +:1092E00041F480119A4201DA002070BD40F233430C +:1092F0009A42A2F2334203DC524200F058F800E0F6 +:1093000090402C43F1D0404270BD00F0004230F05C +:1093100000400AD0C10D01F56071C0F3160042EAA9 +:109320000151C208400711437047002001467047B1 +:1093300001F0004330B421F0004150EA010206D0B0 +:109340000A0DA2F56072C1F31301002A02DC30BCE1 +:1093500000207047440F44EAC104C100E01830BC4B +:1093600000EBC25000F083B8002801DBC0F10040E0 +:10937000002901DBC1F1004181427047002801DB77 +:10938000C0F10040002901DBC1F100418842704773 +:10939000202A04DB203A00FA02F1002070479140B5 +:1093A000C2F1200320FA03F3194390407047202AAA +:1093B00004DB203A21FA02F00021704721FA02F37F +:1093C000D040C2F120029140084319467047202A3C +:1093D00006DBCB17203A41FA02F043EAE07306E0DD +:1093E00041FA02F3D040C2F12002914008431946ED +:1093F0007047A0F14101192900D8203070472DE9AC +:10940000F04791460F4680460446002614F8015B5B +:109410002DB1FFF7F5FB0068405DC007F6D12B2D9D +:1094200002D02D2D18D0641E4A463946204600F041 +:109430003DF927B13968A14201D1C7F80080710513 +:109440004FF002040BD54042002803DD00F032FA51 +:109450000460A007BDE8F08746F48066E4E70028D2 +:10946000F8DA00F027FA04606FF00040F2E7002914 +:10947000A8BF7047401C490008BF20F0010070479A +:1094800010B4B0FA80FC00FA0CF050EA010404BFFA +:1094900010BC704749B1CCF1200421FA04F411FA50 +:1094A0000CF118BF012121430843A3EB0C01CB1D94 +:1094B0000106000A002BBEBF002010BC704700EB65 +:1094C000C35010440029A4BF10BC7047401C490081 +:1094D00008BF20F0010010BC7047F0B4002802DC87 +:1094E000F0BC00207047C0F3C751C0F3160040F431 +:1094F0000000CA0701D14000491E3F2202EB61056E +:10950000002211464FF4000626FA01F31344D41842 +:10951000844201D8001B1A464000491C1729F3DD7C +:109520005100814202D24FF0FF3100E0002102EBF6 +:10953000C550F0BCFFF79BBF10B541000CD0C0F385 +:10954000C751962908DC7E2909DC06DB410204D0DC +:1095500000F0004040F07E5010BD002010BDC1F171 +:109560009604C4F1200100FA01F1E040FFF77FFF0B +:10957000A04010BD10B5002B08DA401C41F10001DD +:1095800092185B411A4301D120F0010010BD2DE972 +:10959000F04D92469B4611B1B1FA81F202E0B0FA69 +:1095A00080F220329046FFF7F3FE04460F4640EA71 +:1095B0000A0041EA0B0153465A46084303D12046AC +:1095C0003946BDE8F08D114653EA010015D0C8F1C7 +:1095D00040025046FFF7EBFE05460E465046594600 +:1095E0004246FFF7D5FE084301D0012000E00020ED +:1095F000054346EAE0762C4337430A984FEA445342 +:10960000A0EB08004FEAD4240A304FF0000244EAED +:1096100047544FEAD72502D500200146D1E701057E +:1096200010196941DDE9084500196941BDE8F04DAF +:10963000A0E770B521F0004303430CD0C1F30A55F5 +:109640000024D5EB040564EB0403D617AD1AB3412F +:1096500002DB0020014670BD201841EB025170BDB5 +:1096600030B5002904DB4FF00044404264EB0101B7 +:10967000002B04DB4FF00044524264EB0303994299 +:1096800008BF904230BD0000064C074D06E0E06880 +:1096900040F0010394E8070098471034AC42F6D339 +:1096A000F6F728FD10C4000830C400082DE9F05F6B +:1096B00082460078002715468B460AF10104B94618 +:1096C000302801D09DB113E014F8010B0127782850 +:1096D00003D0582801D045B10AE00DB1102D07D1B3 +:1096E0000027102514F8010B02E0082500E00A25E8 +:1096F0000026B0460EE005FB080005FB06F1012739 +:1097000001EB10461FFA80F8B6F5803F00D3B9464A +:1097100014F8010B294600F069F80028EBDABBF1D8 +:10972000000F05D00FB1641E00E05446CBF8004096 +:10973000B9F1000F06D000F0BDF802210160C81E8B +:10974000BDE8F09F48EA0640FAE72DE9F04D002316 +:109750001A461B1A8A4103DB00200146BDE8F08D42 +:10976000C1F30A52C1F3130141F480154FF0000B0D +:10977000D10702D100186D41521E0027044640F265 +:10978000FF11384601EB620A3E4680460246002041 +:109790004FF48011FFF70BFEC2197141BB1846EB65 +:1097A0000100B4EB030C75EB000C04D3E41A65EB79 +:1097B000000517460E46241908F101006D41804648 +:1097C0003428E3DDF91946EB0600091BA84103D252 +:1097D0004FF0FF32134601E0002213461BEB070057 +:1097E00046EB0A51BDE8F04DFFF7C4BE3A2800D25F +:1097F000303820F02002412A01D3A2F137008842FC +:1098000001D34FF0FF30704770B501EB020410F840 +:10981000015B15F0070301D110F8013B2A1106D1B5 +:1098200010F8012B03E010F8016B01F8016B5B1ECF +:10983000F9D12B0705D40023521E0FD401F8013BA8 +:10984000FAE710F8013B02F10202A1EB030303E087 +:1098500013F8015B01F8015B521EF9D5A142D6D382 +:10986000002070BD490050EAC12018BF04204A0DF5 +:1098700018BF40F0010040F2FF72B2EB515F08BF29 +:1098800040F00200012808BF05207047410008028F +:1098900018BF04200A0E18BF40F001004FF07F42AD +:1098A00032EA010108BF40F00200012808BF05208C +:1098B0007047000000487047EC0300202DE9F0419C +:1098C0004F1E00EBC7010446D1E9000115461E46B4 +:1098D00037F006020DD02A463346FFF7CAFB7F1E3B +:1098E00004EBC703D3E90023FFF71CFB37F00602A4 +:1098F000F1D1022F25D0042F13D0062F18BFBDE8B9 +:10990000F0812A463346FFF7B4FBD4E90A23FFF778 +:1099100009FB2A463346FFF7ACFBD4E90823FFF7DF +:1099200001FB2A463346FFF7A4FBD4E90623FFF7E1 +:10993000F9FA2A463346FFF79CFBD4E90423FFF7E4 +:10994000F1FA2A463346FFF794FBD4E90223FFF7E6 +:10995000E9FA2A463346FFF78CFBD4E90023BDE839 +:10996000F041FFF7DFBA0000024A00201107FFF7BD +:1099700060BE000001FDFFFF6FF05E010807FFF70A +:10998000C5BA00002DE9F04D0E4614464FF07F4158 +:10999000B1EB440F9EBF4FF0FF313160BDE8F08D59 +:1099A0004FF0004040EA0421C4F3C7507838431117 +:1099B00000F01F00DFF814C1C0F12002FC445CF885 +:1099C00023500CEB83038540D3F804C02CFA02F734 +:1099D0002F439D680CFA00FC25FA02F8DB6805FAB3 +:1099E00000F023FA02F240EA02054CEA080CA7FB59 +:1099F0000132ACFB01C0A5FB015101EB0C058D420E +:109A000034BF4FF0010C4FF0000CC1186144BCF1A1 +:109A1000000F02D0814202D903E0814201D201202D +:109A200000E00020104400F120024FEA9218800666 +:109A3000CA0C40EA42304F03C6F80080FFF7FAFB39 +:109A400082463846FFF7FFFB6FF01201FFF75EFA20 +:109A500007462846FFF7F7FB6FF02501FFF756FA98 +:109A6000834639465046FFF783F95946FFF780F998 +:109A700000F500656FF30B0551462846FFF7CAF95C +:109A80003946FFF7C7F95946FFF7C7F91049FFF7FD +:109A9000C7F907460F492846FFF7C2F93946FFF7CD +:109AA00067F907460C492846FFF7BAF93946FFF728 +:109AB0005FF914F0004F08BFBDE8F08DC8F1805188 +:109AC00080F000403160BDE8F08D000070220000A1 +:109AD000DB0FC92F22AAFD290000C92F02E008C808 +:109AE000121F08C1002AFAD170477047002001E018 +:109AF00001C1121F002AFBD1704700000149086014 +:109B000070470000EC0300202DE9F04104464FF0BF +:109B10000E4000EB4400B0F1506F204620D94FF0CA +:109B2000E441B1EB440F08D9FFF7B0FE042808BFA9 +:109B3000FFF722FF2046BDE8F0814FF07F41B1EBF7 +:109B4000440F04D2BDE8F0410121FFF7DFB9012045 +:109B5000FFF7D4FFBDE8F04100210846FFF796B9B2 +:109B60004FF0FC41B1EB440F1CD224F000404FF009 +:109B70007E51FFF752F94FF0FF31FFF7C7F9054665 +:109B800001F01FF814F0004F1DBF204F204E80F051 +:109B90000040204F08BF204E4FF04041FFF740F9F2 +:109BA000044605E000273E460146FFF739F9054621 +:109BB0001A492846FFF734F91949FFF7D9F8294619 +:109BC000FFF72EF91749FFF7D3F82946FFF728F9D1 +:109BD0001549FFF7CDF82946FFF722F91349FFF79A +:109BE000C7F8804629462046FFF71AF94146FFF795 +:109BF00017F9054631462046FFF7BAF82946FFF720 +:109C0000B7F83946BDE8F041FFF7B2B80000C9BF68 +:109C100022AAFDB90000C93F22AAFD3924FE1C3D3D +:109C2000C78AD83C1E67383D1B93993DAFAA2A3E90 +:109C30002DE9F0474FF0684202EB40030C46054621 +:109C4000B3F1654F3CBF02EB4102B2F1654F3FD328 +:109C50004FF07F42B2EB400F28BFB2EB410F03D26F +:109C6000BDE8F047FFF784B840EA01035B0008BF96 +:109C700044F0FF410AD0B2EB400F08BFB2EB410FF6 +:109C800006D125F0804024F0804105460C461FE0B7 +:109C9000B2EB400F12BF5FEA410245F0FF4004F013 +:109CA000004115D04FEA410292EA400310D4002A45 +:109CB000ACBF4FF09F464FF03E563146FFF7B0F82D +:109CC000054631462046FFF7ABF8044628462146B4 +:109CD000C0F3C753C1F3C7529A1A1B2A06DD10F00E +:109CE000004F14BF54485548BDE8F08712F11A0FD1 +:109CF00017DA11F0004F06D010F0004F14BF504893 +:109D00005048BDE8F08721462846FFF7BFF80446D3 +:109D1000FFF7BCFD042808BFFFF72EFE2046BDE874 +:109D2000F0874200B2EB410F25D910F0004F19BF68 +:109D3000454F464E464F474E224685F00044154655 +:109D40000A4680F0004110460A1A5200B2F1807FA4 +:109D50003ED248404049DFF804A110F0004F18D02F +:109D60004FF03F483846FFF755F807465146304612 +:109D7000FFF750F817E011F0004F04BF00263746F8 +:109D8000E2D010F0004F19BF354F364E364F374EE8 +:109D9000DAE74FF07C583846FEF7EAFF07465146AF +:109DA0003046FEF7E5FF064641462846FFF738F8FD +:109DB0002146FEF7DDFF824621464046FFF730F898 +:109DC0002946FFF72AF85146FFF760F8044604E0F9 +:109DD00021462846FFF75AF804460146FFF720F8C7 +:109DE00080462349FFF71CF82249FEF7C1FF414690 +:109DF000FFF716F82049FEF7BBFF4146FFF710F8C2 +:109E00001E49FEF7B5FF4146FFF70AF81C49FEF769 +:109E1000AFFF054641462046FFF702F82946FEF708 +:109E2000FFFF3146FEF7A4FF2146FEF7A1FF3946AA +:109E3000BDE8F047FEF79CBFDB0FC9BFDB0FC93F92 +:109E4000DB0F49C0DB0F49400000C9BF22AAFDB9A2 +:109E50000000C93F22AAFD390060ED3EC30ACE379B +:109E6000000049C022AA7DBA0000494022AA7D3ADA +:109E70002DAD65BD8FB8D53D0FB511BE61C84C3E47 +:109E8000A8AAAABE2DE9F8430446024651486946ED +:109E9000B0EB420F09D94FF0E640B0EB420F8CBF58 +:109EA0004FF0FF300020009034E04B4B22F0004098 +:109EB00083422BD949492046FEF7B2FFFFF73CFB0E +:109EC0000746FFF7D6F900F00300009044493846F2 +:109ED000FEF7A6FF064643493846FEF7A1FF0546B2 +:109EE00041493846FEF79CFF804640493846FEF718 +:109EF00097FF2146FEF791FF4146FEF78BFF29466B +:109F0000FEF788FF3146FEF785FF02E01046FFF7B7 +:109F100039FD04462546009C002C18DA6800B0F193 +:109F20007F4F3CBF4FF07E50BDE8F88309D14FF022 +:109F30000100FFF7E3FDBDE8F84300210846FEF706 +:109F4000A5BF2846BDE8F8430121FEF7DFBF29463B +:109F500014F0010F08461DD0FEF762FF06462449A3 +:109F6000FEF75EFF2349FEF758FF3146FEF758FF24 +:109F70002149FEF7FDFE3146FEF752FF2946FEF766 +:109F80004FFF2946FEF7F4FE14F0020F18BFBDE89C +:109F9000F8831AE0FEF744FF05461849FEF740FF34 +:109FA0001749FEF7E5FE2946FEF73AFF1549FEF789 +:109FB000DFFE2946FEF734FF4FF07E51FEF7D8FE54 +:109FC00014F0020F08BFBDE8F88380F00040BDE840 +:109FD000F8830000B61F927E490E494683F9223F5E +:109FE0001A61342C0020A23300A0FD390000C93FC3 +:109FF000336D4C39DA82083CA0AA2ABEB93AB2BA0B +:10A00000CA9F2A3DDDFFFFBE2DE9F04D16460F46E3 +:10A010000546020094B01C4621F0004123F00040A8 +:10A0200014BF4FF0010C4FF0000C0CEB470CFE4B33 +:10A030000CEB03084FEA630CC4452DD85FEA060811 +:10A0400018BF4FF0010808EB44089844F74B43450C +:10A0500022D8F74B50EA060C02D09F4205D14AB9EC +:10A0600014B000201946BDE8F08D002A08BF4FF05B +:10A07000000C01D04FF0010C0CEB470313F5001F4F +:10A080000AD8002E14BF4FF0010C4FF0000C0CEB5F +:10A09000440313F5001F08D914B03246234628465E +:10A0A0003946BDE8F04DFEF73DBFDFF888B34FF00D +:10A0B000000A002FB8BF584523DADF4B9842A8BFEB +:10A0C0004FF0020A1DDADA4B98421ADBDB4B03EB46 +:10A0D0002053142B08DDC3F1340C26FA0CF303FAD9 +:10A0E0000CFCB4450DD108E05EB9C3F1140C20FAA4 +:10A0F0000CF303FA0CFC844503D103F00103C3F114 +:10A10000020A51EA020321D1002C1FDA002F18BFE6 +:10A11000BAF1020F02D0BAF1010F0BD00220FFF703 +:10A12000EDFC14B00022BDE8F04D13461046C049C6 +:10A13000FFF711B80220FFF7E1FC14B02A463B46B6 +:10A14000BDE8F04D0020BA49FFF705B833006DD1E6 +:10A15000584525D107F1804010F5801001BF002A35 +:10A160000020B34914B008BFBDE8F08DB04881426B +:10A1700007DB002CA1BF1846214614B0BDE8F08DC6 +:10A1800007E0002CBFBF184684F0004114B0BDE8C2 +:10A19000F08DAB497944D1E9000114B0BDE8F08DF0 +:10A1A000DFF88CC2604526D1002C1FDA19B1594561 +:10A1B00013D15AB11AE0002A40F0DA829D4A39469A +:10A1C00014B0002062F31E01BDE8F08D0020394676 +:10A1D00014B060F31E01BDE8F08D07DA14B03B4601 +:10A1E000BDE8F04D00206146FEF7B5BF14B0104643 +:10A1F0003946BDE8F08D8B4518DDB4F1804F0DD0A8 +:10A20000A4F10053B3F1FF5310D13B1E0EDB14B089 +:10A210001046BDE8F04D194600F0ACBC3B4614B00A +:10A220001046BDE8F04D1946FEF723BF27F0004366 +:10A23000A2BBE1B1594538D1002F06DD002CA1BFEA +:10A240000020594614B0BDE8F08D002F01DD002C30 +:10A250001FDB002F16DA002C14DBBAF1010F4FF0D0 +:10A2600000000CBF7749734914B0BDE8F08DBAF116 +:10A27000020F18BF002F0CD0BAF1010F09D1002F27 +:10A2800007DA0CE0002FB8BF002C0EDABAF1010F8C +:10A2900005D0002014B00146BDE8F08D05E014B0F3 +:10A2A00000204FF00041BDE8F08D4FF0010C0CEBA9 +:10A2B000E7720D9252EA0A020BD0634A90427DDDAA +:10A2C000624B634A984216DD91420EDC002C1CDB87 +:10A2D0002CE00120FFF712FC14B00022BDE8F04D85 +:10A2E000134610461146FEF736BF5148884202DC3D +:10A2F000002C0ADC1AE08A4202DD002C05DB15E0A6 +:10A300004B4B99421EDD002C10DD0220FFF7F6FBBF +:10A3100040F2013200204FF0E041FFF78AF9454A50 +:10A3200014B061F31E021146BDE8F08D0220FFF764 +:10A33000E5FBFFF719FB3E4A14B061F31E0211461C +:10A34000BDE8F08D002228463946FEF78CFE054612 +:10A3500088466FF00102FFF76CF94FF055323D4B24 +:10A36000FEF784FE2A464346FEF783FE00223A4B60 +:10A37000FEF77CFE07468B462A46434610461946A2 +:10A38000FEF777FE3A465B46FEF773FE09910C90A6 +:10A390004FF0C042314B28464146FEF76AFE074661 +:10A3A0008B462F4A2D4B09990C98FEF762FECDE99A +:10A3B00001102C4A2C4B2846414600E019E0FEF7DC +:10A3C00058FEDDE90132FEF74EFE3A465B46059146 +:10A3D0000890FEF7A7FD002588463A465B462846CA +:10A3E000FEF741FE059B089AFEF740FE024600F08C +:10A3F00076B90020B1F5801F07DA352228461946C4 +:10A40000FFF717F905466FF0340000EB2150A0F27A +:10A41000FF300190C1F3130040F07F6141F04051E3 +:10A4200002911249884223E0FFFF1F00FFFF0F0047 +:10A430000000F03F0000F07F0000404301FCFFFF00 +:10A44000901A00000000F0FF0000E0410000F0431F +:10A45000FFFFEF3F5555D53F0000E03F4715F73F61 +:10A46000FE822B6544DF5DF80BAE543E8E980300F0 +:10A47000D8BF4FF0000B0EDDFE498142C8BF4FF040 +:10A48000010B08DC01984FF0000B401C0190029872 +:10A49000A0F580100290F8480299784400EBCB00B8 +:10A4A0000B911090D0E900232846FEF7DCFD0090C8 +:10A4B00010980791D0E9002328460B99FEF732FD4A +:10A4C00002460B460020ED49FEF745FE05910B467E +:10A4D0000246089007990098FEF7CBFD0690E848E1 +:10A4E000884600277844029900680E904FF000508B +:10A4F00040EA610000EB8B4000F5002110980291CA +:10A50000D0E900230E98FEF7AEFD2A460B9BFEF71E +:10A51000ADFD3A464346FEF7ACFD05460B91384685 +:10A520004146029B0E9AFEF7A4FD079B009AFEF798 +:10A530009DFD2A460B9BFEF796FD059B089AFEF7AC +:10A5400098FD0B911090069A434610461946FEF767 +:10A5500090FD05460246CB480B4600910621784403 +:10A56000FFF7ACF9009B2A46029108901046194665 +:10A57000FEF77FFD029B089AFEF77BFD05460591DD +:10A58000434638461946069AFEF7CCFC0B9B109AB8 +:10A59000FEF76FFD2A46059BFEF7C4FC3A4643468C +:10A5A0000591089010461946FEF763FD0022B64B50 +:10A5B00000910C90FEF7B6FC059B089AFEF7B2FCE2 +:10A5C0000D463A46B04B3846FEF74DFD009B0C9ABF +:10A5D000FEF749FD059B089AFEF748FD11913A46A2 +:10A5E0000C902B4610464146FEF743FD0791009024 +:10A5F0004346069A11990C98FEF73BFD804603915D +:10A600002B463A460B991098FEF733FD4246039BC2 +:10A61000FEF788FC059180460B4602460799009894 +:10A62000FEF780FC00200F460546079B009AFEF7C8 +:10A630001AFD4246059BFEF719FD804609914FF031 +:10A640006042924B28463946FEF713FD0091029076 +:10A650008F4A8E4B40460999FEF70BFD80460391C9 +:10A660008C4A8D4B28463946FEF703FD4246039B34 +:10A67000FEF758FC894A7A4402EBCB03D3E9002366 +:10A68000FEF750FC069003910198FEF7E1FD0746A6 +:10A69000DDE902030591069A0099FEF743FC804A22 +:10A6A0007A4402EBCB0BDBE90023FEF73BFC3A4696 +:10A6B000059BFEF737FC002588463A462846059B51 +:10A6C000FEF7D1FCDBE90023FEF7CDFC009B029AEC +:10A6D000FEF7C9FC039B069AFEF7C8FC0246002061 +:10A6E00006900D98654FAAF10103184301D16D4FF3 +:10A6F000069000200B46009030462146FEF7B9FC3C +:10A7000082468B46234630461946009AFEF7ABFC3C +:10A710002A464346FEF7ADFC52465B46FEF702FC76 +:10A7200006468A462A46434621460098FEF7A1FC83 +:10A7300004460D4632465346FEF7F4FB5A4A8B4612 +:10A74000914226DBABEB020353EA000210D1224612 +:10A750002B46FEF788FC80460591544A544B304600 +:10A760005146FEF7DFFB4246059BFEF779FF30D2EC +:10A770000220FFF7C3F940F2013200204FF0E04120 +:10A78000FEF757FF0A46394614B062F31E01BDE8D2 +:10A79000F08D484B2BF000429A421AD3464A0BEBFD +:10A7A000020353EA000208D122462B46FEF75BFC67 +:10A7B00032465346FEF754FF0BD80220FFF79EF9AE +:10A7C000FFF7D2F80A46394614B062F31E01BDE81D +:10A7D000F08D2BF000403949394A01EB20514FF000 +:10A7E0000008904223DD481C4FF4801121FA00F04C +:10A7F0005844C0F30A51334AA1F2FF317A44324B34 +:10A800001268CB4020EA0303C0F3130040F4801C1D +:10A81000C1F114002CFA00F8BBF1000FB8BFC8F169 +:10A82000000820462946FEF71EFC04460D46224637 +:10A830002B4630465146FEF775FB4FF0000B5A464B +:10A84000224B58460591FEF714FC00900791204AD0 +:10A85000204B58460599FEF70CFC049102902246C5 +:10A860002B4658460599FEF7FEFB32465346FEF747 +:10A87000FDFB31E07AB60B007A1600000000F03FD5 +:10A8800040170000E61500000000084009C7EE3F31 +:10A89000FD033ADCF5015B14E02F3EBEBE14000060 +:10A8A000841400000000F0BF00009040FE822B6581 +:10A8B0004715973C00CC904000346F3F01FCFFFFF0 +:10A8C0000000E03F28140000FFFF0F00432EE63F8A +:10A8D000396CA80C615C20BE3F4A404BFEF7C9FBB7 +:10A8E000049B029AFEF71EFB06468A46079B009AC7 +:10A8F000FEF718FB04460D46079B009AFEF7B3FBD4 +:10A9000032465346FEF7B2FB064622462B460991D5 +:10A9100010461946FEF7ADFB8346024630488A468C +:10A920000B4605217844FEF7C9FF5A465346FEF709 +:10A93000A0FB22462B46FEF799FB82468B46324609 +:10A9400020462946099BFEF794FB3246099BFEF7F9 +:10A95000E9FA0591089000224FF08043504659468D +:10A96000FEF781FB0646009152465B46204629468B +:10A97000FEF77FFB3246009BFEF7EDFB059B089A36 +:10A98000FEF771FB22462B46FEF76DFB0022154BAE +:10A99000FEF76CFB0D46044601EB08510815002834 +:10A9A00010DC424620462946FEF743FEFEF75AFFDA +:10A9B000042808BFFEF7D8FF424620462946FEF786 +:10A9C00038FE044606980B4614B022463946BDE8C8 +:10A9D000F04DFEF74EBB0000EF39FAFE422EE63F87 +:10A9E000501200000000F03F2DE9F84304460246F3 +:10A9F00053486946B0EB420F09D94FF0E640B0EB3F +:10AA0000420F8CBF4FF0FF300020009034E04D4BE0 +:10AA100022F0004083422BD94B492046FEF700FA32 +:10AA2000FEF78AFD0746FEF724FC00F003000090C5 +:10AA300046493846FEF7F4F9064645493846FEF7DA +:10AA4000EFF9054643493846FEF7EAF980464249A0 +:10AA50003846FEF7E5F92146FEF7DFF94146FEF7F5 +:10AA6000D9F92946FEF7D6F93146FEF7D3F902E0C7 +:10AA70001046FEF787FF04462546009C002C1DDA91 +:10AA80006800B0F17F4F09D22846FEF7FFFE042888 +:10AA900008BFFEF771FF2846BDE8F88308D1012002 +:10AAA000FFF72CF8BDE8F84300210846FEF7EEB9A1 +:10AAB0002846BDE8F8430121FEF728BA294614F0DC +:10AAC000010F08461ED0FEF7ABF905462349FEF7F5 +:10AAD000A7F92349FEF74CF92946FEF7A1F92149C8 +:10AAE000FEF746F92946FEF79BF94FF07E51FEF737 +:10AAF0003FF914F0020F08BFBDE8F88380F0004072 +:10AB0000BDE8F883FEF78CF906461749FEF788F989 +:10AB10001649FEF782F93146FEF782F91449FEF72D +:10AB200027F93146FEF77CF92946FEF779F92946DF +:10AB3000FEF71EF914F0020FE0D1BDE8F883000023 +:10AB4000B61F927E490E494683F9223F1A61342C82 +:10AB50000020A23300A0FD390000C93FB93AB2BAC3 +:10AB6000CA9F2A3DDDFFFFBE336D4C39DA82083CB7 +:10AB7000A0AA2ABE2DE9F04106460F46FEF7E5FDE4 +:10AB800004000D4618BF0120284320F00040C0F10A +:10AB90007F6000F1E040C00F0FD0002E14BF0120F5 +:10ABA0000020384320F00040C0F17F6000F1E04019 +:10ABB000C00F04BF0120FEF7A1FF20462946BDE8D3 +:10ABC000F08170B50546FEF788FC044620F0004091 +:10ABD000C0F1FF40C00F08D025F00040C0F1FF4099 +:10ABE000C00F04BF0120FEF789FF204670BD0000A2 +:10ABF000C6BC000809BD000844BD0008C3BC00086D +:10AC0000CABC00086FBC00086ABC0008B7BC0008DA +:10AC10005FBC00083EBD000872BC00081ABD0008F9 +:10AC20004ABD000886BC0008E9BC000893BC0008C7 +:10AC300058BC0008E2BC000800000000F7BC000897 +:10AC40002EBD0008D1BC0008FBBC00080FBD0008E9 +:10AC500033BD00089FBC0008AEBC00082ABD000838 +:10AC60007DBC000824BD000854BD000800000000A1 +:10AC700079BC000804BD00088FBC000824BD000892 +:10AC80002ABD00080000000035C3000862BC0008AF +:10AC900050BC00082BC2000800000000B0C2000831 +:10ACA00022C100087703000872C10008C7C100086C +:10ACB00055060008A0C1000835C300089D0600081D +:10ACC0007EBE0008ACBF0008C1060008DEC0000858 +:10ACD00035C300088F070008DAC0000806C1000865 +:10ACE000B907000830C10008E4C100082D080008B9 +:10ACF000CFBE0008B7C10008790600089CC1000853 +:10AD0000F7C100083D09000895C1000889C1000885 +:10AD10006D0C000895C0000835C30008FB0C000846 +:10AD2000D4BD000800000000B404002000000000B2 +:10AD300020000000D1BD000800000000B504002084 +:10AD4000000000006400000092BF00080000000046 +:10AD5000B604002001000000FA0000005EBD0008FB +:10AD600002000000B8040020B0040000A4060000A7 +:10AD700047BE000802000000C404002000000000DC +:10AD8000D007000053BE000802000000C6040020E7 +:10AD900000000000D0070000DDBD00080200000038 +:10ADA000C804002000000000D00700005DBF0008BC +:10ADB00002000000BA04002000000000D0070000DC +:10ADC00066BF000802000000BC0400200000000074 +:10ADD000D00700000DC0000800000000BE040020E5 +:10ADE0000000000001000000DAC2000800000000BE +:10ADF000BF04002000000000C8000000E9C20008F5 +:10AE000000000000C004002000000000C800000096 +:10AE100035BE000802000000C2040020E803000064 +:10AE2000D007000095BE000802000000CA04002000 +:10AE300032000000F201000086BE0008020000009F +:10AE4000CC04002032000000F2010000B2BE000875 +:10AE50000400000020050020B004000000C2010032 +:10AE6000C2BE00080400000010050020B00400006D +:10AE700000C2010056C1000800000000B704002015 +:10AE800000000000010000001CBE000800000000DF +:10AE9000A80400200A000000C8000000FBBD000854 +:10AEA00000000000A90400200A0000003200000099 +:10AEB000E8BD000800000000AA0400200A0000000D +:10AEC00032000000C0BF000800000000AB040020FA +:10AED0000000000009000000ADC0000801000000F3 +:10AEE000E6040020FFFFFFFF0100000026BE00086F +:10AEF00002000000E804002000000000D00700006D +:10AF000089C0000802000000EA04002000000000E0 +:10AF1000D0070000A4C2000802000000EC040020DA +:10AF200000000000D00700006CC000080200000014 +:10AF3000EE04002000000000D0070000A4BD0008BF +:10AF400002000000F004002000000000D007000014 +:10AF500087C2000802000000F20400200000000088 +:10AF6000D00700007AC0000802000000F4040020AE +:10AF700000000000D0070000B2BD00080200000081 +:10AF8000F604002000000000D007000095C2000871 +:10AF900002000000F804002000000000D0070000BC +:10AFA0006FBF000801000000FA040020FFFFFFFF50 +:10AFB00001000000E3C0000801000000FB040020C5 +:10AFC000FFFFFFFF0100000081BF0008010000003B +:10AFD000FC040020FFFFFFFF01000000F5C0000897 +:10AFE00001000000FD040020FFFFFFFF0100000042 +:10AFF00065C10008000000000005002000000000FE +:10B00000FF0000001AC0000801000000FE0400203C +:10B010009CFFFFFF640000002CC00008010000003E +:10B02000FF0400209CFFFFFF640000004BC00008ED +:10B03000020000000205002064000000B80B0000C0 +:10B0400066C2000802000000040500206400000041 +:10B05000B80B000083BD00080200000006050020B8 +:10B0600064000000B80B00005CC000080200000093 +:10B070000805002064000000B80B000077C200083B +:10B08000020000000A05002064000000B80B000068 +:10B0900094BD0008020000000C05002064000000C0 +:10B0A000B80B00004BC2000801000000660400203D +:10B0B000FDFFFFFF03000000CDC2000801000000FB +:10B0C00067040020FDFFFFFF0300000029C3000804 +:10B0D0000100000068040020FDFFFFFF03000000E6 +:10B0E00033C200080100000069040020FDFFFFFFDB +:10B0F00003000000B5C20008010000006A0400203F +:10B10000FDFFFFFF0300000011C300080100000065 +:10B110006B040020FDFFFFFF030000003FC200089A +:10B12000010000006C040020FDFFFFFF0300000091 +:10B13000C1C20008010000006D040020FDFFFFFFF8 +:10B14000030000001DC30008010000006E04002081 +:10B15000FDFFFFFF0300000071BE000800000000BB +:10B160006F040020000000000300000036C100084A +:10B17000000000007004002000000000FA00000041 +:10B18000FCC2000800000000710400200100000063 +:10B19000FA00000027BF000803000000640400203C +:10B1A000D4FEFFFF2C010000F8BF000803000000E0 +:10B1B00062040020D4FEFFFF2C010000F9BE00084D +:10B1C00002000000740400200000000000010000E4 +:10B1D00045C1000802000000760400206400000061 +:10B1E000E80300000EBE0008000000007C04002000 +:10B1F0000000000001000000D4BE000800000000B4 +:10B200007D0400200000000030000000EABE0008BD +:10B210000500000080040020000000000100000084 +:10B22000E2BE0008050000008404002000000000C9 +:10B2300001000000C1BD00080000000088040020DB +:10B2400000000000800000009DC000080300000016 +:10B2500060040020B0B9FFFF5046000068BE00083F +:10B26000000000000E0500200000000003000000A8 +:10B27000C6C00008000000003204002000000000EA +:10B28000C800000049BF0008000000003C04002086 +:10B2900000000000C80000006FBD000800000000B2 +:10B2A0004604002000000000C8000000BBC00008E9 +:10B2B000000000003304002000000000C80000006F +:10B2C0003EBF0008000000003D0400200000000018 +:10B2D000C800000064BD0008000000004704002012 +:10B2E00000000000C8000000D0C0000800000000FE +:10B2F0003404002000000000C800000053BF000814 +:10B30000000000003E04002000000000C800000013 +:10B3100079BD000800000000480400200000000083 +:10B32000C80000007BC100080200000014050020D6 +:10B3300000000000D007000002BF0008000000006D +:10B340001805002000000000010000003DC00008BA +:10B35000020000001A0500200A000000D0070000CB +:10B3600058C20008020000001C0500200A0000006E +:10B37000D0070000A4BE0008000000001705002050 +:10B3800000000000640000005FBE00080200000032 +:10B390002C040020000000002823000036BF000815 +:10B3A000000000002F04002000000000C800000082 +:10B3B0001FBF00080000000039040020000000004A +:10B3C000C800000017BF0008000000004304002070 +:10B3D00000000000C800000006C0000800000000D7 +:10B3E0002E04002000000000C8000000F1BF00088B +:10B3F000000000003804002000000000C800000029 +:10B40000EABF000800000000420400200000000025 +:10B41000C800000025C20008000000003004002021 +:10B4200000000000C80000001FC20008000000006B +:10B430003A04002000000000C800000019C2000803 +:10B44000000000004404002000000000C8000000CC +:10B45000B1C100080000000031040020000000001D +:10B46000C8000000ABC10008000000003B04002041 +:10B4700000000000C8000000A5C100080000000096 +:10B480004504002000000000C8000000E2BF0008E2 +:10B49000000000003504002000000000C80000008B +:10B4A000DABF0008000000003F0400200000000098 +:10B4B000C8000000D2BF00080000000049040020BE +:10B4C00000000000C80000004145525431323334BE +:10B4D00000000000000000000000FEFD0100000070 +:10B4E0000000803F00000000A8AAAA3F0000000062 +:10B4F0000000803F000080BFB0AA2ABF000000000B +:10B500000000803F0000803FB0AA2ABF000000007A +:10B510000000803F000000000000803F000080BF6E +:10B520000000803F000080BF000000000000803F5E +:10B530000000803F0000803F000000000000803FCE +:10B540000000803F00000000000080BF000080BFBE +:10B550000000803F000080BF0000803F000080BFEF +:10B560000000803F000080BF000080BF0000803FDF +:10B570000000803F0000803F0000803F0000803FCF +:10B580000000803F0000803F000080BF000080BFBF +:10B590000000803F0000803F00000000000000002D +:10B5A0000000803F000080BF00000000000000009D +:10B5B0000000803F00000000A8AAAA3F0000803FD2 +:10B5C0000000803F000080BFB0AA2ABF000080BFFB +:10B5D0000000803F0000803FB0AA2ABF000080BF6B +:10B5E0000000803F00000000A8AAAA3F000080BF22 +:10B5F0000000803F000080BFB0AA2ABF0000803F4B +:10B600000000803F0000803FB0AA2ABF0000803FBA +:10B610000000803F000080BFD0B35D3F0000803F4E +:10B620000000803F000080BFD0B35DBF000080BF3E +:10B630000000803F0000803FD0B35D3F0000803FAE +:10B640000000803F0000803FD0B35DBF000080BF9E +:10B650000000803F00000000D0B35DBF0000803FCD +:10B660000000803F00000000D0B35D3F000080BFBD +:10B670000000803F000000000000803F000080BF0D +:10B680000000803F000080BF000080BF000000007D +:10B690000000803F000000000000803F0000803F6D +:10B6A0000000803F0000803F000080BF00000000DD +:10B6B0000000803FD0B35DBF0000803F0000803FAE +:10B6C0000000803FD0B35DBF000080BF0000803F1E +:10B6D0000000803FD0B35D3F0000803F000080BF8E +:10B6E0000000803FD0B35D3F000080BF000080BFFE +:10B6F0000000803FD0B35DBF00000000000080BFAD +:10B700000000803FD0B35D3F000000000000803F9C +:10B710000000803F000080BF0000803F000080BF2D +:10B720000000803F000080BF000080BF0000803F1D +:10B730000000803F0000803F0000803F0000803F0D +:10B740000000803F0000803F000080BF000080BFFD +:10B750000000803F000080BF0000803F0000803F6D +:10B760000000803F000080BF000080BF000080BF5D +:10B770000000803F0000803F0000803F000080BF4D +:10B780000000803F0000803F000080BF0000803F3D +:10B790000000803FF704353FF70435BF0000803FCD +:10B7A0000000803FF70435BFF70435BF0000803F3D +:10B7B0000000803FF70435BFF704353F0000803FAD +:10B7C0000000803FF704353FF704353F0000803F1D +:10B7D0000000803F00000000000080BF000080BF2C +:10B7E0000000803F000080BF00000000000080BF1C +:10B7F0000000803F000000000000803F000080BF8C +:10B800000000803F0000803F00000000000080BF7B +:10B810000000803F0000803F000000BF0000803F2C +:10B820000000803F000000BF000080BF0000803F9C +:10B830000000803F000080BF0000003F0000803F0C +:10B840000000803F0000003F0000803F0000803F7C +:10B850000000803F0000003F000080BF000080BF6C +:10B860000000803F000080BF000000BF000080BFDC +:10B870000000803F000000BF0000803F000080BF4C +:10B880000000803F0000803F0000003F000080BFBC +:10B890000000803F000000000000803F0000803F6B +:10B8A0000000803F000080BF000080BF000000005B +:10B8B0000000803F000000000000803F000080BFCB +:10B8C0000000803F0000803F000080BF000000803B +:10B8D000000000000000000003010000E0B40008C8 +:10B8E0000400000010B500080400000050B5000876 +:10B8F0000201000090B500080001000000000000F7 +:10B9000006000000B0B500080600000010B60008F0 +:10B9100001010000000000000400000070B60008F3 +:10B9200006000000B0B600080800000010B70008CC +:10B930000800000090B700080800000010B80008D8 +:10B9400001010000000000000001000000000000F4 +:10B9500000010000000000000400000090B8000892 +:10B960000000000000000000414E474C453B484F9E +:10B9700052495A4F4E3B4241524F3B4D41473B4348 +:10B98000414D535441423B43414D545249473B4141 +:10B99000524D3B47505320484F4D453B4750532055 +:10B9A000484F4C443B50415353544852553B4845F3 +:10B9B0004144465245453B4245455045523B4C4526 +:10B9C000444D41583B4C4C49474854533B484541F2 +:10B9D0004441444A3B00524F4C4C3B50495443482D +:10B9E0003B5941573B414C543B506F733B506F7335 +:10B9F000523B4E6176523B4C4556454C3B4D414780 +:10BA00003B56454C3B00000080250000004B0000E9 +:10BA10000096000000E1000000C201004AC30008D7 +:10BA20006CC30008B6C30008D8C3000836C30008BA +:10BA30008EC30008A2C30008FBC30008B56206015C +:10BA40000300F00500FF19B56206010300F00300D2 +:10BA5000FD15B56206010300F00100FB11B5620699 +:10BA6000010300F00000FA0FB56206010300F002C6 +:10BA700000FC13B56206010300F00400FE17B56276 +:10BA8000060103000102010E47B562060103000131 +:10BA900003010F49B56206010300010601124FB50B +:10BAA00062060103000112011E67B5620616080056 +:10BAB00003070300510800008A41B562060806002A +:10BAC000C80001000100DE6A1048494A4B4C4D4451 +:10BAD000454647FF202122232425262748494A4B53 +:10BAE0004C4DFF1048498A8B8C8D84858687FF20BA +:10BAF0002122232425262748498A8B8C8DFF00008C +:10BB0000000C014008001000000C01401000100063 +:10BB10000008014000101400000000000000F03F89 +:10BB2000000000000000F83F0000000000000000DE +:10BB30000000004003B8E23F0000000000000000E9 +:10BB400006D0CF43EBFD4C3E033333333333E33F77 +:10BB5000FFAB6FDBB66DDB3F4D268F515555D53FA3 +:10BB600001411DA96074D13F65DBC9934A86CD3F71 +:10BB7000EF4E454A287ECA3F3E5555555555C53F5F +:10BB800093BDBE166CC166BF2CDE25AF6A56113F51 +:10BB9000F16BD2C541BDBBBED0A4BE726937663E53 +:10BBA00000404040404040404040414141414140D0 +:10BBB0004040404040404040404040404040404085 +:10BBC0004005020202020202020202020202020214 +:10BBD0000220202020202020202020020202020219 +:10BBE0000202909090909090101010101010101071 +:10BBF000101010101010101010101010020202027D +:10BC000002028888888888880808080808080808C0 +:10BC100008080808080808080808080802020202BC +:10BC200040000000A1BB0008000000000000000070 +:10BC3000000000006E83F9A22915444ED15727FC5D +:10BC4000C0DD34F5999562DB4190433CAB6351FE16 +:10BC50004D50553630353000565441494C3400591A +:10BC600034004144584C3334350048455836005967 +:10BC700036004F43544F5838004143430046414932 +:10BC80004C5341464500414952504C414E45004DB0 +:10BC900041470048454C495F39305F4445470047BC +:10BCA00059524F5F534D4F4F5448494E47004C45F2 +:10BCB000445F52494E4700464C59494E475F5749E9 +:10BCC0004E47004249005452490047494D42414CB9 +:10BCD00000494E464C494748545F4143435F434106 +:10BCE0004C00435553544F4D0048454C495F313249 +:10BCF000305F4343504D0050504D005350454B541E +:10BD000052554D004241524F005155414450004D53 +:10BD10004F544F525F53544F50004F43544F464C73 +:10BD200041545000534F4E41520047505300564229 +:10BD3000415400534552564F5F54494C54004845B6 +:10BD4000583658005155414458004F43544F464CC3 +:10BD50004154580054454C454D45545259006D6965 +:10BD6000647263006770735F706F73725F64006703 +:10BD700070735F706F735F64006770735F6E61767E +:10BD80005F640067696D62616C5F70697463685FAE +:10BD90006D69640067696D62616C5F726F6C6C5F86 +:10BDA0006D69640077696E675F6C6566745F6D6965 +:10BDB000640077696E675F72696768745F6D696454 +:10BDC000006D6F726F6E5F7468726573686F6C641C +:10BDD000007961776465616462616E64006D696EAB +:10BDE000636F6D6D616E6400766261746D696E6320 +:10BDF000656C6C766F6C7461676500766261746DFA +:10BE0000617863656C6C766F6C74616765006D70EA +:10BE100075363035305F7363616C650076626174CE +:10BE20007363616C65007472695F7961775F6D69D6 +:10BE300064646C65006661696C736166655F7468F3 +:10BE4000726F74746C65006D696E7468726F74746F +:10BE50006C65006D61787468726F74746C65006CE9 +:10BE60006F6F7074696D65006770735F747970656A +:10BE7000006163635F686172647761726500666523 +:10BE8000617475726500736572766F5F70776D5F50 +:10BE900072617465006D6F746F725F70776D5F7241 +:10BEA000617465006E61765F736C65775F72617453 +:10BEB000650073657269616C5F626175647261745B +:10BEC00065006770735F62617564726174650073A9 +:10BED000617665006261726F5F7461625F73697A37 +:10BEE00065006261726F5F6366006261726F5F6EB0 +:10BEF0006F6973655F6C7066006779726F5F6C70F5 +:10BF000066006E61765F636F6E74726F6C735F68EC +:10BF1000656164696E6700645F7069746368006975 +:10BF20005F7069746368006163635F7472696D5FF9 +:10BF3000706974636800705F70697463680067702B +:10BF4000735F706F73725F69006770735F706F7398 +:10BF50005F69006770735F6E61765F69006D696E1F +:10BF6000636865636B006D6178636865636B00701F +:10BF7000697463685F646972656374696F6E5F6C2E +:10BF800000726F6C6C5F646972656374696F6E5F79 +:10BF90006C00616C745F686F6C645F7468726F745E +:10BFA000746C655F6E65757472616C006C69737436 +:10BFB000206F72202D76616C206F722076616C008C +:10BFC000706F7765725F6164635F6368616E6E65F1 +:10BFD0006C00645F6C6576656C00695F6C657665A6 +:10BFE0006C00705F6C6576656C00645F726F6C6C82 +:10BFF00000695F726F6C6C006163635F7472696D7E +:10C000005F726F6C6C00705F726F6C6C0072657445 +:10C0100061726465645F61726D0067696D62616C15 +:10C020005F70697463685F6761696E0067696D62FC +:10C03000616C5F726F6C6C5F6761696E006E6176D8 +:10C040005F73706565645F6D696E0067696D6261DD +:10C050006C5F70697463685F6D696E0067696D62BB +:10C06000616C5F726F6C6C5F6D696E0077696E6793 +:10C070005F6C6566745F6D696E0077696E675F728D +:10C08000696768745F6D696E007472695F79617762 +:10C090005F6D696E0076657273696F6E006D6167C2 +:10C0A0005F6465636C696E6174696F6E0079617756 +:10C0B0005F646972656374696F6E006770735F7047 +:10C0C0006F73725F70006770735F706F735F700083 +:10C0D0006770735F6E61765F70006D617000686598 +:10C0E0006C700070697463685F6469726563746919 +:10C0F0006F6E5F7200726F6C6C5F646972656374FF +:10C10000696F6E5F72006D617070696E67206F6637 +:10C11000207263206368616E6E656C206F72646567 +:10C12000720064657369676E20637573746F6D2048 +:10C130006D69786572006163635F6C70665F6661EC +:10C1400063746F72006779726F5F636D70665F66AC +:10C150006163746F72007370656B7472756D5F6884 +:10C16000697265730067696D62616C5F666C6167B7 +:10C17000730064656661756C7473006770735F77D4 +:10C18000705F7261646975730073686F772073798B +:10C190007374656D207374617475730073657400D6 +:10C1A0006578697400645F616C7400695F616C74C8 +:10C1B00000705F616C74007361766520616E64204D +:10C1C0007265626F6F7400726573657420746F209E +:10C1D00064656661756C747320616E64207265625B +:10C1E0006F6F74006D69786572206E616D65206F88 +:10C1F00072206C697374006E616D653D76616C755B +:10C2000065206F7220626C616E6B206F72202A2035 +:10C21000666F72206C69737400645F79617700697E +:10C220005F79617700705F796177004D4D413834F7 +:10C23000357800616C69676E5F6163635F78006188 +:10C240006C69676E5F6D61675F7800616C69676ECE +:10C250005F6779726F5F78006E61765F7370656596 +:10C26000645F6D61780067696D62616C5F706974AD +:10C2700063685F6D61780067696D62616C5F726FA2 +:10C280006C6C5F6D61780077696E675F6C65667472 +:10C290005F6D61780077696E675F72696768745F68 +:10C2A0006D6178007472695F7961775F6D617800A4 +:10C2B000636D697800616C69676E5F6163635F7964 +:10C2C00000616C69676E5F6D61675F7900616C69C1 +:10C2D000676E5F6779726F5F79006661696C736121 +:10C2E00066655F64656C6179006661696C7361663F +:10C2F000655F6F66665F64656C6179006163635F4B +:10C300006C70665F666F725F76656C6F6369747977 +:10C3100000616C69676E5F6163635F7A00616C697D +:10C32000676E5F6D61675F7A00616C69676E5F67FA +:10C3300079726F5F7A0024504D544B3235312C3175 +:10C34000393230302A32320D0A0024505542582CEE +:10C3500034312C312C303030332C303030312C31E2 +:10C36000393230302C302A32330D0A0024505542F5 +:10C37000582C34312C312C303030332C303030319B +:10C380002C33383430302C302A32360D0A00245009 +:10C390004D544B3235312C33383430302A32370D4E +:10C3A0000A0024504D544B3235312C35373630305D +:10C3B0002A32430D0A0024505542582C34312C3176 +:10C3C0002C303030332C303030312C353736303063 +:10C3D0002C302A32440D0A0024505542582C343156 +:10C3E0002C312C303030332C303030312C31313551 +:10C3F0003230302C302A31450D0A0024504D544B38 +:10C400003235312C3131353230302A31460D0A0087 +:10C4100030C4000800000020F00300000898000865 +:10C42000D4C40008F0030020581A0000EC9A000859 +:10C43000410228220351093DCBDC050201A0CBDEDD +:10C44000050271021103022C018B803F0401DEE220 +:10C4500003124045080140018A1C1032029A041060 +:10C4600032049A081032082A0C104A041042408AFA +:10C470001D102A800B69104A0C609A081029602A46 +:10C480000C103B2C01301129211A1B056910196170 +:10C490002A0C104A083039602A1E45491039609923 +:10C4A000102940AA081019611A0C1013D4BA1B08DD +:10C4B000C8041AEF041AE3040144B94584A24A04EB +:10C4C000380C010203040607080902040623291098 +:04C4D0006914C1002A +:04000005080000ED02 +:00000001FF diff --git a/src/baseflight/obj/baseflight_fy90q.hex b/src/baseflight/obj/baseflight_fy90q.hex new file mode 100644 index 0000000000..d686463921 --- /dev/null +++ b/src/baseflight/obj/baseflight_fy90q.hex @@ -0,0 +1,2540 @@ +:020000040800F2 +:1000000028190020F9820008498300084B83000862 +:100010004D8300084F830008518300080000000052 +:1000200000000000000000000000000053830008F2 +:100030005583000800000000578300080F6900087E +:100040005B8300085B8300085B8300085B83000818 +:100050005B8300085B8300085B8300085B83000808 +:100060005B8300085B8300085B8300085B830008F8 +:100070005B8300085B830008656B00085B830008F6 +:100080005B8300085B8300085B8300085B830008D8 +:100090005B8300085B8300085B8300085B830008C8 +:1000A0005B8300085B8300085B8300085B830008B8 +:1000B000897100085B8300085B83000815670008EE +:1000C00037630008256700081D6700085B83000888 +:1000D0005B8300085B830008D36D00085B83000826 +:1000E0005B8300085B8300085B830008DFF80CD0AB +:1000F00008F0D8FB00480047FB160008281900202C +:10010000F0B504460E461546B4FBF5F038B1B4FB25 +:10011000F5F72A4631463846FFF7F2FF0646B4FBAC +:10012000F5F005FB1040FDA1085C3070701CF0BDBF +:1001300070B505460C461646022E01DB242E00DD66 +:100140000A26002D09DA2D2020703246611C6842F3 +:10015000FFF7D6FF0021017006E03246214628460F +:10016000FFF7CEFF00210170204670BD10B5F5A04D +:1001700006F0E3FD10BD2DE9F04105460C462F4683 +:100180002646306808F075F980463168424638687E +:1001900008F077F9BDE8F08110B50446EBA006F051 +:1001A000CCFD012000F08FFEEFA006F0C6FD0A2076 +:1001B00006F0D8FB002006F083FC10BD10B5044605 +:1001C000EDA006F0BAFD002000F048FEEDA006F01C +:1001D000B4FD0A2006F0C6FB002006F071FC10BD3D +:1001E00010B50446EBA006F0A8FD2021EF4808F06A +:1001F00015F90020EE490860EE4908702046FFF727 +:10020000DDFF10BD2DE9F0410546284608F031F923 +:10021000064600F0C6FF0746E6B9E7A006F08DFDEA +:10022000002400BFE94850F8240000B90DE0012087 +:10023000A040384204D0E54951F8240006F07DFD85 +:10024000202006F066FD641CECE700BFC5A006F0A8 +:1002500074FD5BE03246DEA1284608F012F9C8B909 +:10026000DDA006F06AFD002400BFD84850F8240045 +:1002700000B909E0D54951F8240006F05EFD2020C0 +:1002800006F047FD641CF0E700BFB6A006F055FD80 +:10029000BDE8F0814FF0000828782D2803D14FF0F9 +:1002A00001086D1C761E002400BFC84850F82400C9 +:1002B00018B9CFA006F041FD26E0C44850F824103C +:1002C0003246284608F0DDF8E0B9B8F1000F08D052 +:1002D000012101FA04F000F05EFFCCA006F02DFD34 +:1002E00007E0012101FA04F000F0E0FDCAA006F0E9 +:1002F00024FDB64951F8240006F01FFD99A006F030 +:100300001CFD01E0641CD0E700BF00BF00BFBFE7D9 +:1003100070B505460024C3A006F00FFD00BF1AE02B +:1003200004EB4401C54A52F8210006F006FD0920FD +:1003300006F0EFFC04EB4401C04A02EB810148687F +:1003400006F0FBFC87A006F0F8FC00BF06F0BEFC40 +:100350000028FBD0641C0A2CE2D370BDFEB5054614 +:10036000284608F086F80646082E20D1002404E02E +:10037000285D08F011F82855641C082CF8D30024D7 +:1003800010E0295DAE4808F06BF830B1295D2A19FC +:10039000501C08F065F800B903E0AAA006F0CDFCF7 +:1003A000FEBD641C082CECD3284600F09DFCADA0DB +:1003B00006F0C3FC002406E0A148015DAF48005DE3 +:1003C0000DF80010641C082CF6D300200DF8040072 +:1003D000684606F0B2FC63A006F0AFFC00BFDFE7A2 +:1003E00070B50646304608F044F8C5B27DB9A4A001 +:1003F00006F0A3FCA1496B394978491EA44A52F87A +:10040000210006F09AFC57A006F097FC70BD2A4622 +:100410006FA1304608F035F8C8B99EA006F08DFCF3 +:10042000002400BF9A4850F8240000B90AE0984917 +:1004300051F8240006F081FC202006F06AFC601CC4 +:10044000C4B2EFE700BF47A006F077FCDEE7002468 +:1004500000BF8F4850F8240018B993A006F06DFC37 +:100460001AE08B4850F824102A46304608F009F864 +:1004700078B9601C81496B39487091A006F05DFC29 +:10048000834951F8240006F058FC36A006F055FCCC +:1004900002E0601CC4B2DCE700BF00BFB6E77FB576 +:1004A00004460D4600262079052815D2DFE800F025 +:1004B00003060A0D1100A06806780DE0A06890F907 +:1004C000006009E0A068068806E0A068B0F9006056 +:1004D00002E0A068066800BF00BF0A2269463046F5 +:1004E000FFF726FE684606F028FCADB149A006F0ED +:1004F00024FC0A226946E068FFF71AFE684606F007 +:100500001CFC44A006F019FC0A2269462069FFF78A +:100510000FFE684606F011FC7FBD0000303132331B +:100520003435363738394142434445464748494ACD +:100530004B4C4D4E4F505152535455565758595A93 +:10054000000000000D0A23200000000052657365C2 +:100550007474696E6720746F2064656661756C746D +:10056000732E2E2E0D0A00005265626F6F74696E35 +:10057000672E2E2E00000000536176696E672E2EC6 +:100580002E0000000D0A5265626F6F74696E672E4F +:100590002E2E00000D0A4C656176696E6720434C73 +:1005A00049206D6F64652E2E2E0D0A008C030020ED +:1005B0000000002013020020456E61626C6564201B +:1005C00066656174757265733A2000004C00002006 +:1005D0006C69737400000000417661696C61626C43 +:1005E000652066656174757265733A2000000000CD +:1005F000496E76616C696420666561747572652008 +:100600006E616D652E2E2E0D0A0000004469736127 +:10061000626C656420000000456E61626C65642058 +:1006200000000000417661696C61626C6520636F57 +:100630006D6D616E64733A0D0A0000002891000828 +:10064000049700084D75737420626520616E7920EF +:100650006F72646572206F662041455452313233A7 +:10066000340D0A0043757272656E7420617373698C +:10067000676E6D656E743A2000000000170400205C +:1006800043757272656E74206D697865723A2000E8 +:1006900004000020417661696C61626C65206D69BF +:1006A000786572733A200000496E76616C69642047 +:1006B0006D6978657220747970652E2E2E0D0A0092 +:1006C0004D697865722073657420746F2000000096 +:1006D0000279052A10D2DFE802F0030407080C00B3 +:1006E00000BF8368197007E000BF0AB283681A80F0 +:1006F00002E08268116000BF00BF70472DE9F0473B +:1007000080464FF000090027404607F0B2FE05463C +:100710002DB1012D28D198F800002A2824D1F5A068 +:1007200006F00BFB00241CE004EB8400F74901EB0E +:10073000800604EB8401F54A52F8210006F0FDFA28 +:10074000F3A006F0FAFA29463046FFF7A8FEAFF20A +:10075000EC1006F0F2FA00BF06F0B8FA0028FBD061 +:10076000641C452CE0D353E0EAA1404607F062FE4A +:100770005FEA00094CD009F101096D1E484607F0F7 +:1007800099FE074600243EE004EB8400DF4901EBBC +:10079000800604EB8401DD4A52F8210007F069FE6F +:1007A000824604EB8400D94A52F820105246404653 +:1007B00007F067FE30BB04EB8400D44901EB8000F6 +:1007C000C068B84219DC04EB840001EB80000069CA +:1007D000B84212DB39463046FFF77AFF04EB84015A +:1007E000CA4A52F8210006F0A8FACBA006F0A5FAF2 +:1007F00000213046FFF753FE02E0CAA006F09DFA42 +:10080000BDE8F087641C452CBED3D0A006F095FA55 +:1008100000BFF5E72DE9FF410746D4A006F08DFAA9 +:1008200006F091F84FF47A71B0FBF1F60A226946AE +:100830003046FFF77DFC684606F07FFACFA006F051 +:100840007CFA0A226946D2480078FFF771FC6846B4 +:1008500006F073FACFA006F070FA0A226946D04873 +:100860000078FFF765FC684606F067FACDA006F051 +:1008700064FA00F084FC0546CEA006F05EFA00247F +:1008800000BFD14850F8240000B90EE00120A0407C +:10089000284204D0CC4951F8240006F04EFA20201A +:1008A00006F037FA601CC4B2EBE700BF012000F08D +:1008B00051FC48B1C5A006F040FAC649C64A1278B4 +:1008C00051F8220006F039FAAFF2683006F035FA36 +:1008D000C2A006F032FA0A226946C4480088FFF72F +:1008E00027FC684606F029FAC1A006F026FA05F0B2 +:1008F000E4FF06460A226946FFF71AFC684606F03E +:100900001CFAAFF2A03006F018FABDE8FF8110B56E +:100910000446BBA006F011FA10BD2DE9FF41C44802 +:10092000007838B90120C2490870C2A006F005FA63 +:10093000FFF71CFCCCE106F0D3F90446092C01D0EA +:100940003F2C69D100260027C848D0F80080C84D48 +:100950000FE0C648006838B1C44829680268C54835 +:1009600007F08FFD00B103E006B92E462F4600BF09 +:100970000C35BF4878308542EBD34EB300BFBB493E +:1009800030680968405CB94A39681268895C8842F5 +:1009900000D01CE0B54930680968405C48B92021A6 +:1009A000B24802680068401CB04B1860B1488154DE +:1009B0000DE0AE4930680968405CAE49AB4A126848 +:1009C0008854AA480068401CA8490860D7E700BFBF +:1009D000A648006808B1BE4211D0A7A006F0ADF944 +:1009E000354606E0286806F0A8F9092006F091F9D6 +:1009F0000C35BD42F6D9FFF7B9FB4FF0000806E011 +:100A00009C4911F8080006F084F908F1010897489C +:100A100000688045F4D35AE19448006830B9042C4A +:100A200004D19448FFF7DCFBBDE8FF810C2C05D115 +:100A300093A006F082F9FFF799FB48E18B48006824 +:100A4000002836D00A2C01D00D2C32D10025AFF26F +:100A5000EC4006F072F900208649844A12688854F6 +:100A6000084601900020029088480C230A22804901 +:100A7000009001A807F096FC05464DB1286807F0E4 +:100A8000F8FC7C490844461C3046A968884702E0C7 +:100A90007FA006F052F92021764807F0BFFC002025 +:100AA000724908606248007800B9BDE7FFF75EFB55 +:100AB0000DE17F2C0ED16D480068C8B100216B4854 +:100AC0000068401E694A10606A4A115479A006F015 +:100AD00034F9FCE065480068202809D2202C07DBA7 +:100AE0007E2C05DC6148006818B9202C01D1EFE0AC +:100AF000EDE0E1E043757272656E742073657474A5 +:100B0000696E67733A200D0A00000000A09100088A +:100B1000203D20003D0000002073657420746F208C +:100B2000000000004552523A2056616C7565206104 +:100B3000737369676E6D656E74206F7574206F6670 +:100B40002072616E67650D0A000000004552523A3E +:100B500020556E6B6E6F776E207661726961626C84 +:100B600065206E616D650D0A000000005379737495 +:100B7000656D20557074696D653A2000207365635A +:100B80006F6E64732C20566F6C746167653A200039 +:100B9000AC010020202A20302E31562028000000F1 +:100BA00064010020532062617474657279290D0A12 +:100BB0000000000044657465637465642073656EAD +:100BC000736F72733A200000800000204143434855 +:100BD000573A200098000020FC0100204379636C04 +:100BE000652054696D653A20000000003401002042 +:100BF0002C20493243204572726F72733A200000F4 +:100C00004166726F333220434C49207665727369B6 +:100C10006F6E20322E30204A756C203230203230F8 +:100C20003132202F2032333A35323A34340000004A +:100C3000130200200D0A456E746572696E672043C9 +:100C40004C49204D6F64652C2074797065202765B0 +:100C50007869742720746F2072657475726E2C2009 +:100C60006F72202768656C70270D0A000000002055 +:100C7000289100088C0300200D1B5B4B0000000036 +:100C80001B5B324A1B5B313B314800007701000897 +:100C90004552523A20556E6B6E6F776E20636F6DC2 +:100CA0006D616E642C20747279202768656C7027E2 +:100CB0000000000008200800094801680068401C86 +:100CC000074A106007484454204606F022F800BF47 +:100CD00005F0EFFF00287FF42EAE00BFA4E6000071 +:100CE000000000208C03002070B5064634460CE05E +:100CF0002178FE4807F0B4FB05462DB1A01BC1B218 +:100D0000FA482A1AFA488154641C20780028EFD146 +:100D100070BD70B5BC22F749F5486B3807F065FB2C +:100D2000002419E0F2486B3890F8291004FB04F015 +:100D30001938484300F6C4106043ED496B3991F807 +:100D40002810484340F6C41190FBF1F000B2EA4984 +:100D500021F81400601CC4B2062CE3DB002454E02C +:100D600004EB8402E24B6B3B93F82A30C3EB420066 +:100D70000121002806DDDE4A6B3A92F82A20C2F1F2 +:100D80006402D1B2002803DAD94A6B3A92F82A10E9 +:100D9000D74A6B3A92F82B2000FB00F35A4301FB31 +:100DA00001F392FBF3F2D24B6B3B93F82B30C3F180 +:100DB00064031A4442430A2392FBF3F2CC4B6B3B8D +:100DC00093F82A300A2505FB032212B2CB4B23F8F5 +:100DD0001420C74A6B3AB2F88620C54B6B3BB3F878 +:100DE0008430D21AC54B33F914305A434FF47A7316 +:100DF00092FBF3F2BE4B6B3BB3F884301A4412B251 +:100E0000BE4B23F81420601CC4B20B2CA8DBB848DE +:100E10006B38B0F89000B6496B39B1F8921088423F +:100E200004DAB3486B38B0F8920012E0B0486B387F +:100E3000B0F89000AE496B39B1F89410884204DDE7 +:100E4000AB486B38B0F8940003E0A9486B38B0F8B1 +:100E50009000A7496B39A1F8900070BD70B50646A7 +:100E600007F0D6F9342007F03DFAA24807F0FEF962 +:100E7000042810D100240BE09D4A6B3A11599D4A79 +:100E8000A01807F00FFA0546042D00D002E0241D3B +:100E9000BC2CF1D300BF07F0C1F9FFF73AFF26B130 +:100EA000012214210F2001F0C3FD70BD90496B3960 +:100EB000496801438E4A6B3A5160704700208C4963 +:100EC0006B394860704770B505468A48067825B981 +:100ED0008B480078864200D170BD894800788449EB +:100EE0006B39087003204870FFF7E8FF0220FFF716 +:100EF000DDFF40F6B8307E496B39088128208872C2 +:100F00001E20087517208877282179486B38C17210 +:100F10001E2141751721C177552101732D2181753E +:100F2000002180F82010102141730F21C175072185 +:100F300080F821100B2181730021017680F82210A6 +:100F40001421C173082141762D2180F823100E2130 +:100F5000017414218176502180F8241046214174B7 +:100F60000A21C176142180F82510282181740021DE +:100F7000C174417780F827105A205D496B3981F898 +:100F80002800412081F82900002081F82C0081F8F8 +:100F90002D0081F82E00322081F82A00002081F8EF +:100FA0002B00002406E0002151481F3820F81410BF +:100FB000601CC4B20E2CF6DB00204D496B39C8878B +:100FC00000214B486B38A0F84010002048496B398D +:100FD0000886002146486B384186818600204449B6 +:100FE0006B39888781F84200042081F843004FF470 +:100FF000C870A1F846002A20A1F84400414888643E +:101000006E2081F868002B2081F86900212081F88A +:101010006A003DA0FFF768FE002035496B3981F872 +:10102000730081F87400142081F87500002081F8A5 +:10103000760040F2DC50A1F8780040F24C40A1F874 +:101040007A0040F26C70A1F87C00002081F87E00EC +:101050000A2081F87F00C82081F880004FF4966054 +:10106000A1F8820040F27E40A1F8840040F23A707C +:10107000A1F886004FF47A70A1F888004FF4C87088 +:10108000A1F88A003220A1F88C00012081F88E009E +:1010900040F2DC50A1F890004FF47F70A1F892006C +:1010A0004FF4FA60A1F894000A2081F8960081F8C4 +:1010B0009700012081F898004FF47F70A1F89A0002 +:1010C0004FF4FA60A1F89C0040F2DC50A1F89E00B9 +:1010D0004FF47F70A1F8A0004FF4FA60A1F8A200CD +:1010E00040F2DC50A1F8A40014E0000004970008CE +:1010F0001704002000FC01080C0500201805002042 +:10110000B0000020031414004145545231323334EE +:10111000000000004FF41650C1F8A800C820A1F844 +:10112000AC00142081F8AE001E2081F8AF00012031 +:1011300081F8B0006420A1F8B2004FF49670A1F8D5 +:10114000B4004FF4E130C1F8B8000020FFF786FE8C +:1011500000BFC1E6014614480068084201D00120E2 +:1011600070470020FCE71049096801430E4A1160EE +:1011700070470D49096881430B4A116070470A485E +:1011800000687047014609484068084201D00120C4 +:1011900070470020FCE7054949688143034A5160D4 +:1011A0007047024840687047AC000020AC03002044 +:1011B00070B5FE48008807F061FA0546FC4907F063 +:1011C000DEF9044607F05FFA00B2FA49088070BD04 +:1011D0002DE9F04104460D462946204607F0DEFC85 +:1011E0000746F54907F0CBF9064607F04CFA00B27E +:1011F000BDE8F0812DE9FE4304460D4694E8070062 +:101200008DE807000199686807F0B9F90746009969 +:10121000286807F0B4F98046394607F058F90646C1 +:10122000A16807F0A9F9A0600199A86807F0A7F9DB +:1012300007460299286807F0A2F98046394607F068 +:1012400098F90646216807F042F920600099A868DD +:1012500007F095F907460299686807F090F980460B +:10126000394607F034F90646616807F030F96060E6 +:10127000BDE8FE832DE9FF5F002505F04EFB064625 +:10128000CE490968701A07F0F9F98046CC4907F091 +:1012900076F90746C948066000245FE0C94931F97C +:1012A000140007F0E2F98046394607F068F901A911 +:1012B00041F82400C44890F8430000283CDDC249AE +:1012C00091F8430007F0DAF9834659464FF07E5013 +:1012D00007F08BF98246BD4931F9140007F0C5F9D2 +:1012E0005146009007F04BF98046B74991F843000A +:1012F00007F0C4F9014600904FF07E5007F075F9F1 +:1013000083464FF07E5107F037F98246B04850F8D7 +:101310002410504607F033F98146414607F0D7F8CC +:10132000AB4941F8240051F8240007F0ACF900B2B1 +:10133000A84921F8140005E0A44830F81400A54994 +:1013400021F81400A34830F91400A24931F914100F +:1013500000FB01550420FFF7FDFE641C032C9DD308 +:101360006420684391490988494390FBF1F501A93C +:101370009948FFF73FFF0420FFF7ECFE18B101A9E1 +:101380009648FFF737FF9348B0F90000002803DDC7 +:101390009048B0F9000003E08E48B0F900004042E8 +:1013A0008449B1F9001088421ADA8A48B0F902007B +:1013B000002803DD8748B0F9020003E08548B0F952 +:1013C000020040427B49B1F90010884208DA8148A6 +:1013D000B0F90400002803DD01208149487302E0D0 +:1013E00000207F494873242D01DDC42D02DB7C4899 +:1013F000407B90B300242EE07349B1F8460007F01B +:101400003DF983464FF07E5107F061F88246514620 +:101410004FF07E5007F0E9F880466E4931F914002C +:1014200007F023F968490090B1F8460007F026F963 +:101430008346694850F82410584607F0A0F88246C1 +:10144000009907F044F88146414607F098F8624950 +:1014500041F82400641C032CCED30420FFF77AFE4D +:10146000D8B1002417E05F4931F9140007F0FDF806 +:1014700081465A4951F824005B4907F080F88246BA +:10148000494607F024F88046584907F078F8534950 +:1014900041F82400641C032CE5D34F4A916810687E +:1014A000FFF796FE524908804B4A91685068FFF753 +:1014B0008FFE4F494880BDE8FF9F1FB50120FFF711 +:1014C00049FE18B102F04CFDFFF7D4FE02F0CFFD4B +:1014D00000240EE03B4830F8140002A921F8140063 +:1014E0000120FFF737FE18B90020384921F8140011 +:1014F000641C032CEED305F010FA3E49086001F09D +:10150000B9FA05F00AFA3B490968401A40F28A2103 +:10151000884206D938480088401C00B23649088005 +:1015200009E000BF05F0F9F932490968401A40F2B4 +:101530008A218842F6D302F09AFD002427E0214850 +:1015400030F8140002A931F81410084400B22DF844 +:1015500014003DF91400294931F9141008440321FD +:1015600090FBF1F000B2264921F814003DF9140077 +:1015700000EBD0714910214A22F814100120FFF726 +:10158000E9FD18B90020114921F81400641C032C4E +:10159000D5D34020FFF7F6FDB0B31A480078A0BBC2 +:1015A0000948806C000C174908702FE0FA010020F0 +:1015B0007593D83EB40000204C3D0F44E800002055 +:1015C00053449231EC000020AC030020F2000020D4 +:1015D00080040020F800002068040020740400202B +:1015E000FC040020FE000020000048435E06A33BF0 +:1015F000CC000020D800002036010020D0000020C0 +:10160000C0000020DE00002027E006E01E48806CBD +:10161000000A48701C48806C887000241AE01B483F +:1016200030F914101A4830F914201A48005D401E91 +:1016300002FB0010401C1749095D90FBF1F000B25D +:10164000124921F81400084630F81400104921F816 +:101650001400641C032CE2D315E00B4840780128E9 +:1016600011D10A48B0F904100B48B0F9000001EBA1 +:101670004000032190FBF1F000B204498880084645 +:101680008088054908801FBDAC030020C0000020F1 +:10169000E2000020DE000020DC00002070B5684879 +:1016A000007808B1022000E00020054605F0CFFEDA +:1016B000401BC6B24FF40040624908602C4607E068 +:1016C0006148B0F88610204605F0B2FE601CC4B236 +:1016D000B442F5DB40F6B83005F044F92C4606E09C +:1016E0004FF47A71204605F0A3FE601CC4B2B442E8 +:1016F000F6DB042005F0C1F970BD1CB505F03EF91C +:10170000FFF707FB0020FFF7DEFB4F49D1F8B800D9 +:1017100002F0A6FD0120FFF726FD00F0A7F801204A +:10172000FFF730FD8DF801000820FFF72BFD80F05A +:1017300001008DF800004248007808B1012000E067 +:1017400000208DF80200404890F89800C0F3C000D7 +:101750008DF803003C48B0F88A00ADF804003A4820 +:10176000B0F88C00ADF80600684605F0C2FD08B17F +:10177000FFF794FF3548364908604FF4004031497F +:101780000860C01033490861002415E02D4808386E +:10179000006880F400402B49083908602D48C06873 +:1017A00080F480502B49C860192005F0DBF819201F +:1017B00005F0D8F8601CC4B20A2CE7DB4FF4805067 +:1017C00024490861C0001F49091F086002F078FA27 +:1017D000FFF7EEFC0220FFF7D5FC08B102F094FA07 +:1017E0000820FFF7CFFC28B104F05BF91A4818492C +:1017F00008600DE00120FFF7C5FC48B14FF4807090 +:10180000FFF7C0FC20B11049D1F8A80004F061F83E +:1018100005F083F8114908600B484078052803D18A +:101820004FF4C8700E4908804FF47A700D49088053 +:1018300001200D49487301E001F010FCFCE70000B5 +:101840001501002014080140AC0300206D2F000892 +:101850004C01002000100140D95A0008300100203E +:10186000F6010020F8010020FC04002010B5F94822 +:10187000407804280BD0F7484078012807D0F54875 +:101880004078052803D0F3484078082802D1012089 +:10189000F14908702020FFF775FC10B10120EE49D6 +:1018A0000870EC48407812282DD2DFE800F02C15A3 +:1018B000191A110920210D1B222627282C2C2C1C3B +:1018C0000020E64908701EE00120E44908701AE093 +:1018D0000220E249087016E00320E049087012E097 +:1018E00000BF00BF00BF0420DC4908700BE000BF50 +:1018F00000BF0620D949087005E000BF00BF0820DE +:10190000D649087000BF00BF10BD10B5D24800789E +:1019100000B910BDCF484078012803D0CD484078A9 +:10192000042810D1CE48008981B2002005F080FD46 +:10193000C8484078042812D1C948408981B20120A2 +:1019400005F076FD0BE0C648008881B2002005F066 +:101950006FFDC348408881B2012005F069FD00BFDA +:10196000D7E770B50025BC48007800B102250024F7 +:1019700009E0BC4A32F8142091B26219D0B205F0E5 +:1019800057FD601CC4B2B54800788442F1DB70BDDD +:1019900070B50546002404E0B24820F81450601CDD +:1019A000C4B2AE4800788442F6DBFFF7DAFF70BDC0 +:1019B000F8B5AA48007803284DDDAB48B0F904100B +:1019C000AA48B0F90400002803DDA848B0F90400D3 +:1019D00003E0A648B0F9040040426FF06302101A19 +:1019E000814210DAA148B0F90400002803DD9F48C5 +:1019F000B0F9040003E09D48B0F9040040426FF0E4 +:101A00006301081A24E09848B0F904109748B0F927 +:101A10000400002803DD9548B0F9040003E0934872 +:101A2000B0F904004042643081420EDD8F48B0F9C5 +:101A30000400002803DD8D48B0F9040003E08B4862 +:101A4000B0F904004042643002E08748B0F9040075 +:101A500000B2854988807F48407812287ED2DFE82E +:101A600010F07D00920007014B011200FF05D50127 +:101A700063027D009A01F302A303400407057D0081 +:101A80007D007D00C4057948C188774800880844F6 +:101A900000B2744908807548C08873490988494272 +:101AA000084400B26F4948806A4890F98E006E4938 +:101AB000B1F90410484300F2DC506B49B1F902104F +:101AC0000844B0F57F7F02DA4FF47F701FE0614871 +:101AD00090F98E006449B1F90410484300F2DC50DB +:101AE0006149B1F902100844B0F5FA6F02DD4FF414 +:101AF000FA600CE0574890F98E005B49B1F9041088 +:101B0000484300F2DC505849B1F90210084400B2D1 +:101B1000534908814F4890F98E005349B1F9041098 +:101B2000484300F2DC505049B1F90210401AB0F5B8 +:101B30007F7F02DA4FF47F7021E0464890F98E00F3 +:101B40004949B1F90410484300F2DC504649B1F963 +:101B50000210401AB0F5FA6F04DD00E073E24FF4B2 +:101B6000FA600CE03B4890F98E003F49B1F904104F +:101B7000484300F2DC503C49B1F90210401A00B26F +:101B8000374948815FE23848B0F9020080000321FC +:101B900090FBF1F03549C988084400B2314908800A +:101BA0003148B0F9020040004042032190FBF1F1BE +:101BB0002E48C0882C4A128852421044084400B271 +:101BC000284948802848B0F90200400040420321DB +:101BD00090FBF1F12548C28823480088104408444E +:101BE00000B2204988801B48B0F89000194991F94B +:101BF0008E101D4AB2F9042001FB02001549B1F80C +:101C00009210884203DA1348B0F892001EE011489F +:101C1000B0F890000F4991F98E10134AB2F90420E0 +:101C200001FB02000B49B1F89410884203DD09481A +:101C3000B0F894000AE00748B0F89000054991F91F +:101C40008E10094AB2F9042001FB020000B20449D7 +:101C5000088197E7AC030020150100201401002043 +:101C6000160100208C040020C2010020B0010020D9 +:101C7000FE48C0880146FE4840880144FD4890F96E +:101C80008E00FB4A928850434042084400B2FA4911 +:101C90000880F648C088F649098849420844014648 +:101CA000F44890F98E00F24A928800FB021000B2CC +:101CB000F1494880ED48C188ED4800880844014654 +:101CC000EC4890F98E00EA4A928800FB021000B2BC +:101CD000E9498880E548C088E54949884942014486 +:101CE000E44890F98E00E24A92885043404208440A +:101CF00000B2E149C88045E7DC48C088DC49098872 +:101D000049420144DA4840880144DA4890F98E009B +:101D1000D74A928850434042084400B2D6490880CE +:101D2000D248C088D249098849420844D0494988E4 +:101D300049420144CF4890F98E00CD4A928800FB79 +:101D4000021000B2CC494880C848C188C848008801 +:101D50000144C74840880144C64890F98E00C44AEF +:101D6000928800FB021000B2C3498880BF48C18836 +:101D7000BF4800880844BE49498849420144BD48DB +:101D800090F98E00BA4A928850434042084400B20B +:101D9000B949C880F6E6B548C0880146B4484088CD +:101DA0000144B44890F98E00B14A928850434042B1 +:101DB000084400B2B0490880AC48C088AC490988E2 +:101DC00049420844AA4949884942084400B2AA49FC +:101DD0004880A648C0880146A54840880144A548D7 +:101DE00090F98E00A24A928800FB021000B2A2492C +:101DF00088809E48C1889E48008808449C4949883C +:101E00004942084400B29C49C880BBE69848B0F9F2 +:101E100002008000032190FBF1F09449C98801443D +:101E2000944890F98E00924A928800FB021000B20A +:101E3000914908808E48B0F90200400040420321D9 +:101E400090FBF1F08949C988894A128852421144AD +:101E50000144884890F98E00854A92885043404258 +:101E6000084400B2844948808148B0F9020040002B +:101E70004042032190FBF1F27C48C1887C480088F5 +:101E8000084411187B4890F98E00794A9288504393 +:101E90004042084400B2784988807548B0F9020091 +:101EA0008000032190FBF1F07049C988014471481A +:101EB00090F98E006E4A928850434042084400B226 +:101EC0006D49C8806A48B0F90200400040420321D1 +:101ED00090FBF1F06549C988654A12885242114465 +:101EE0000144644890F98E00614A928800FB021018 +:101EF00000B2614908815E48B0F9020040004042EA +:101F0000032190FBF1F15948C288594800881044D8 +:101F10000144584890F98E00554A928800FB0210FF +:101F200000B2554948818EE0514AB2F90020514231 +:101F300001EBD1724D4BDB8803EB62034C4AB2F9E3 +:101F4000020000EBD07203EB62034A4A92F98E2042 +:101F5000474EB68802FB063212B2474B1A80444AFB +:101F6000B2F90020514201EBD172404BDB8803EB08 +:101F700062023F4BB3F90230584200EBD07302EBE0 +:101F800063033C4A92F98E20394EB688724352421E +:101F90001A4412B2384B5A80354AB2F9001001EB9C +:101FA000D172324BDB8803EB6203314AB2F9020093 +:101FB00000EBD07203EB62032E4A92F98E202C4E76 +:101FC000B68802FB063212B22B4B9A80284AB2F92D +:101FD000001001EBD172254BDB8803EB6202244B2E +:101FE000B3F90230584200EBD07302EB6303214A8D +:101FF00092F98E201E4EB688724352421A4412B293 +:102000001D4BDA801948C088194949884942014462 +:10201000184890F98E00164A928800FB021000B210 +:10202000194608811148C08801461148408801447A +:10203000104890F98E000E4A92885043404208445E +:1020400000B219464881AEE30948B0F900008000AB +:102050004042052190FBF1F00449C9880844044935 +:10206000B1F9021001EBC1010A2207E0B001002022 +:10207000C2010020AC0300208C04002091FBF2F18F +:102080000144F74890F98E00F64A928800FB02104E +:1020900000B2F5490880F348B0F9000080004042E2 +:1020A000052190FBF1F0F149C9880844ED49B1F9E7 +:1020B0000210494201EBC1010A2291FBF2F10144F5 +:1020C000E74890F98E00E74A928800FB021000B2C0 +:1020D000E5494880E348B0F900008000052190FB05 +:1020E000F1F0E249C9880844DE49B1F9021001EB78 +:1020F000C1010A2291FBF2F10144D94890F98E0006 +:10210000D84A928850434042084400B2D649888059 +:10211000D448B0F900008000052190FBF1F0D349CC +:10212000C9880844CF49B1F90210494201EBC10105 +:102130000A2291FBF2F10144C94890F98E00C94A84 +:10214000928850434042084400B2C749C880C548FD +:10215000B0F9000080004042052190FBF1F0C34936 +:10216000C98808440146BE4890F98E00BD4A92884D +:1021700050434042084400B2BB490881B948B0F915 +:1021800000008000052190FBF1F0B849C98808449F +:102190000146B34890F98E00B24A928800FB0210C3 +:1021A00000B2B1494881FEE2B048C088AD49098813 +:1021B00049420144AB4840880144A94890F98E0047 +:1021C000A84A928850434042084400B2A649088079 +:1021D000A648C088A349098849420844A1494988BA +:1021E000494201449E4890F98E009E4A928800FB25 +:1021F000021000B29C4948809C48C18899480088D8 +:102200000144984840880144954890F98E00954AC9 +:10221000928800FB021000B2934988809348C188DD +:102220009048008808448F494988494201448C48B5 +:1022300090F98E008B4A928850434042084400B285 +:102240008949C8808948C08886490988494201442B +:10225000844840880144824890F98E00814A9288DF +:1022600000FB021000B2804908818048C0887D4987 +:102270000988494208447B494988494201447848D1 +:1022800090F98E00774A928850434042084400B249 +:10229000754948817548C188724800880144714871 +:1022A000408801446E4890F98E006E4A92885043EF +:1022B0004042084400B26C4988816C48C188694832 +:1022C000008808446749498849420144644890F9B4 +:1022D0008E00644A928800FB021000B26249C881F5 +:1022E00061E26048B0F90000C0EBC0000A2190FB39 +:1022F000F1F05E49C98808445A49B1F90210A1EBCE +:10230000C1010A2291FBF2F10144554890F98E0077 +:10231000544A928800FB021000B253490880514889 +:10232000B0F90000A0EBC0000A2190FBF1F04F498A +:10233000C98808444B49B1F90210A1EBC1010A2236 +:1023400091FBF2F10144464890F98E00454A92888B +:1023500000FB021000B2444948804248B0F9000036 +:10236000A0EBC0000A2190FBF1F04049C988084465 +:102370003C49B1F90210C1EBC1010A2291FBF2F113 +:102380000144374890F98E00364A928800FB0210CB +:1023900000B2354988803348B0F90000C0EBC00076 +:1023A0000A2190FBF1F03149C98808442D49B1F95F +:1023B0000210C1EBC1010A2291FBF2F1014428484D +:1023C00090F98E00274A928800FB021000B226493D +:1023D000C8802648C088234949884942014420488A +:1023E00090F98E001F4A928850434042084400B240 +:1023F0001D4908811D48C0881A4909884942084476 +:102400000146174890F98E00164A92885043404280 +:10241000084400B2144948811448C0880146114854 +:10242000408801440E4890F98E000E4A928850432D +:102430004042084400B20C4988810C48C1880948D0 +:10244000008808440146064890F98E00054A9288A3 +:1024500050434042084400B20349C881A3E1000050 +:10246000AC030020C20100208C040020B001002039 +:10247000FE49CA88FE4909881144FD4AB2F9022082 +:10248000504200EBD07201EB6202FA4991F98E10D2 +:10249000F74B9B8801FB032109B2F74A1180F449ED +:1024A000B1F90010484200EBD071F04AD28802EB3B +:1024B0006101EF4A528852420A44EE4991F98E1066 +:1024C000EB4B9B8801FB032109B2EB4A5180E749A2 +:1024D000C988E74A128852420A44E549B1F9020024 +:1024E00000EBD07102EB6102E24991F98E10E04BF2 +:1024F0009B8801FB032109B2DF4A9180DC49B1F9D5 +:10250000000000EBD071D94AD28802EB6102D849B1 +:1025100049880A44D74991F98E10D54B9B8801FB15 +:10252000032109B2D44AD180D149B1F9000000EBAE +:10253000D071CE4AD28802EB6101CD4A5288524214 +:102540000A44CC4991F98E10C94B9B8859434942A2 +:10255000114409B2C84A1181C449C988C44A1288C1 +:1025600052421144C24AB2F90220504200EBD072EA +:1025700001EB6202BF4991F98E10BD4B9B88594314 +:102580004942114409B2BC4A5181B949B1F900101C +:10259000484200EBD071B54AD28802EB6102B449DF +:1025A00049880A44B34991F98E10B14B9B8859432D +:1025B0004942114409B2B04A9181AC49CA88AC4938 +:1025C00009880A44AA49B1F9020000EBD07102EB74 +:1025D0006102A84991F98E10A54B9B885943494245 +:1025E000114409B2A44AD181DDE0A048C088014667 +:1025F0009F48408801449F4890F98E009C4A9288E9 +:1026000000FB021000B29C4908809848C088984995 +:10261000098849420844964949884942084400B219 +:10262000954948809148C0880146914840880144B6 +:10263000904890F98E008E4A928850434042084458 +:1026400000B28D4988808948C1888948008808443B +:10265000874949884942084400B28749C880A2E0B6 +:10266000844B93F99630854EB6F9026003FB06F26F +:10267000D31702EB13737F4EB6F89E6006EB23135D +:102680007A4EB6F9026033447A4EB6F89A60B34295 +:1026900003DA784BB3F89A3030E0764B93F9963002 +:1026A000764EB6F9026003FB06F1CB1701EB13730C +:1026B000704EB6F89E6006EB23136C4EB6F90260BE +:1026C00033446C4EB6F89C60B34203DD694BB3F8FB +:1026D0009C3013E0674B93F99630684EB6F9026070 +:1026E00003FB06F0C31700EB1373624EB6F89E604F +:1026F00006EB23135D4EB6F9026033441BB2604E05 +:1027000033805C4B93F997305C4EB6F9006003FB65 +:1027100006F2D31702EB1373564EB6F8A46006EB1D +:102720002313524EB6F900603344524EB6F8A060FF +:10273000B34203DA4F4BB3F8A03030E04D4B93F97E +:1027400097304E4EB6F9006003FB06F1CB1701EB54 +:102750001373484EB6F8A46006EB2313434EB6F944 +:1027600000603344434EB6F8A260B34203DD414BF0 +:10277000B3F8A23013E03F4B93F997303F4EB6F9D0 +:10278000006003FB06F0C31700EB1373394EB6F875 +:10279000A46006EB2313354EB6F9006033441BB238 +:1027A000374E738000BF00BF2020FEF7EBFC0028EF +:1027B0006DD0002000902F4890F8980010F0010F85 +:1027C00005D12C4890F8980010F0020F08D02D4841 +:1027D00080892849B1F87810401A80B2ADF800001D +:1027E000244890F8980010F0040F08D12548C089BB +:1027F0002049B1F87810401A80B2ADF802001D48A7 +:10280000B0F89E00BDF80010084400B21C490880D2 +:102810001848B0F8A400BDF80210084400B21849E6 +:1028200048801948C07888B3124991F99610134A24 +:10283000B2F9022001FB02F0C11700EB1171104A3E +:10284000128802EB211109B20D4A1180094991F950 +:1028500097100A4AB2F9002001FB02F0C11700EB01 +:102860001171074A528802EB211111E0B0010020DA +:10287000C2010020AC0300208C040020CC0000200A +:10288000160100203C0100202E05002003E03FE05F +:1028900009B2614A51806048B0F900005F49B1F85F +:1028A0009A10884203DA5D48B0F89A000EE05A4860 +:1028B000B0F900005949B1F89C10884203DD57482F +:1028C000B0F89C0002E05448B0F9000000B2524950 +:1028D00008800846B0F902005049B1F8A0108842BB +:1028E00003DA4E48B0F8A0000EE04B48B0F9020001 +:1028F0004A49B1F8A210884203DD4848B0F8A20066 +:1029000002E04548B0F9020000B24349488000BFE8 +:10291000424890F8980010F0080F0DD0002409E00C +:10292000221D3F4B33F8122091B2A21DD0B204F009 +:102930007FFD641C042CF3D33A48B0F90050012405 +:1029400008E0384830F91400A84202DD354830F973 +:102950001450641C344800788442F2D3002455E0BB +:102960002E48B0F88600A8420BDA2E4830F8140042 +:102970002A49B1F88610691A401A00B2294921F88B +:102980001400284830F914002449B1F88410884212 +:1029900003DA2248B0F884000EE0224830F914002F +:1029A0001E49B1F88610884203DD1C48B0F8860045 +:1029B00002E01C4830F9140000B21A4921F8140052 +:1029C0001748B0F906001549B1F87A10884212DAB2 +:1029D0001020FEF7D7FB38B91048B0F8840000B2D9 +:1029E000104921F8140006E00C48B0F8880000B245 +:1029F0000C4921F814000D48407830B90748B0F868 +:102A0000880000B2074921F81400641C06480078C9 +:102A10008442A5D3F8BD000016010020AC030020BD +:102A20003C0100208C04002014010020FC04002044 +:102A30002DE9F04104460D4616464FF0000815E01A +:102A400000270AE0FA48C06880F48050F849C8605E +:102A5000284603F087FF781CC7B2A742F2DB3C2070 +:102A600003F080FF08F1010000F0FF08B045E7DB4C +:102A7000BDE8F0812DE9F04F87B04FF00008ED4838 +:102A8000B0F9060040F2DC51884201DA64271CE00C +:102A9000E848B0F90600B0F5FA6F10DAE64890F8A9 +:102AA0002E00E449B1F90610A1F2DC5148434FF47D +:102AB000FA7190FBF1F0C0F16400C7B205E0DE48A6 +:102AC00090F82E00C0F16400C7B20024BFE0D948DE +:102AD00030F91400D849B1F87810401A002807DD01 +:102AE000D44830F91400D449B1F87810401A06E0FF +:102AF000D148B0F87800CF4931F91410401AB0F538 +:102B0000FA7F18DACB4830F91400CB49B1F87810C5 +:102B1000401A002807DDC74830F91400C649B1F84B +:102B20007810401A09E0C448B0F87800C14931F97A +:102B30001410401A01E04FF4FA7085B2022C40D014 +:102B4000BD4890F8730058B1BB4890F87300A84294 +:102B500005DAB94890F87300281A85B200E000251C +:102B6000642095FBF0F086B2B449701C31F9100076 +:102B700031F91610401A06EBC60101EB0611A5EB60 +:102B800081014843642190FBF1F0AC4931F8161003 +:102B9000084400B2AA4921F81400A74890F82C0074 +:102BA00068434FF4FA7190FBF1F0C0F1640000F05B +:102BB000FF0A0AFB07F0642190FBF1F000F0FF0A26 +:102BC0001FE09D4890F8740058B19B4890F874003D +:102BD000A84205DA984890F87400281A85B200E0F7 +:102BE000002528B2964921F81400934890F82D004A +:102BF00068434FF4FA7190FBF1F0C0F1640000F00B +:102C0000FF0A8D480A30005D00FB0AF0642190FB4A +:102C1000F1F08C49085588481E30005D00FB0AF031 +:102C2000642190FBF1F088490855824830F914007E +:102C30008149B1F87810884207DA814830F81400E9 +:102C4000404200B27E4921F81400601CC4B2032C3B +:102C5000FFF63DAF7748B0F906007749B1F87A1032 +:102C6000884203DA7448B0F87A000BE07148B0F992 +:102C70000600B0F5FA6F02DD4FF4FA6002E06D482D +:102C8000B0F9060085B26C48B0F87A00281A4FF403 +:102C90007A7148436849B1F87A10C1F5FA61B0FB1E +:102CA000F1F085B2642095FBF0F086B26749701CA4 +:102CB00031F9100031F91610401A06EBC60101EB8C +:102CC0000611A5EB81014843642190FBF1F05F49B7 +:102CD00031F81610084400B25949C8805C48407A5F +:102CE000002855D05B49B1F900105B4AB2F90020C9 +:102CF000881A05F0BAFC5949029005F040FC834659 +:102D0000574905F072FC0690069806F071F8059098 +:102D1000069806F02DF904904949B1F9000005F034 +:102D2000A4FC0090049905F02AFC83464449B1F9BB +:102D3000020005F09AFC0090059905F020FC594628 +:102D4000019005F0C4FB029005F09DFC00B20390D9 +:102D50003B49B1F9020005F088FC0090049905F0A8 +:102D60000EFC37490290B1F9000005F07EFC00909E +:102D7000059905F004FC0190029905F0FAFB8346E1 +:102D800005F081FC00B22E4908800398488000BFFE +:102D90000220FEF7F7F9E8B332480078401CC0B2D1 +:102DA00030490870062190FBF1F201FB120060BB74 +:102DB00004F010F92C4991F800B00978491C2A4A0E +:102DC00011704FEAEB710BEB5171C910ABEBC10104 +:102DD000264A22F811004FF0000909E0234830F894 +:102DE000190040441FFA80F809F1010000F0FF09C2 +:102DF000B9F1080FF2DBC3464FEAE87108EB5171F5 +:102E0000C81000F063FF1A49087019480078194982 +:102E1000098800E035E0884206DC074890F86A003F +:102E200013490978884229DD00201349087028E0F9 +:102E3000001001403C010020AC0300200C050020E4 +:102E4000B0010020B8010020BE01002018050020BC +:102E5000FC0400200E020020AA010020DB0F4940E4 +:102E6000000034436D0100206E0100209C0400200E +:102E7000AC010020F40100206C0100200420FE4978 +:102E80000870FD48007802F00DFFFC48008800281B +:102E900003DD0120FEF75EF918B9F9480088002823 +:102EA00006DDF848C06880F48050F649C8601BE031 +:102EB000F548C07818B14FF48050F2490861F248E3 +:102EC000407818B14FF48050EE4948614FF40060EB +:102ED000FEF758F940B1EC49497809B1012100E009 +:102EE0000021084603F0BEF8E8480068E849096890 +:102EF000884215D9E448407B78B90020E249C8707F +:102F0000E048C06880F48050DE49C860DF4800684F +:102F1000E0490844DE49086002E00120DA49C8704F +:102F200001F09EFC1020FEF715F9A8B1D748006803 +:102F3000D949096888420FD9D848007805280BDBA1 +:102F4000D2480068D6490844D3490860D54800688B +:102F500080F40040D3490860D348C06818B1D24813 +:102F6000C168D248884707B0BDE8F08F70B5054604 +:102F7000CF49485D04F065FA044640F2EE208442F1 +:102F800003DB40F6CA00844203DDC9486B38B0F861 +:102F90007840204670BD70B5C6480078401CC549D1 +:102FA0000870002457E02046C3490968884700B2EA +:102FB000C0490E78F11706EB91718910A6EB8101DB +:102FC000BE4A02EBC40222F811000020BC4921F8DD +:102FD000140000250EE0B94800EBC40030F81500DD +:102FE000B74931F81410084400B2B54921F814006B +:102FF000681CC5B2042DEEDBB14931F91410881CF0 +:10300000C11700EB91718910AD4A22F814101046D7 +:1030100030F91410AB4830F91400C01E814207DAB1 +:10302000104630F81400801C00B2A64921F81400A4 +:10303000A34830F91410A34830F91400C01C814291 +:1030400007DD9F4830F81400801E00B29D4921F82A +:103050001400601CC4B2082CA5DB70BD2DE9F04F34 +:1030600089B00020079002F034FD08B1FFF793FF0C +:10307000864800689449096888427DD98348006879 +:1030800044F620610844904908600820FEF77AF869 +:1030900008B9FFF780FF4FF40070FEF773F80028BF +:1030A00054D083486B3890F87F0000EB800087494C +:1030B000B1F90010884231DA7348407870B30025C6 +:1030C00009E07B486B38B0F8780000B27D4921F800 +:1030D0001500681CC5B2032DF3DB75486B38B0F8DA +:1030E000820000B27749C88071486B3890F87F0041 +:1030F0006F496B3991F88010084400EB80007349E8 +:10310000B1F90010884203DA00205F494870087066 +:103110006F480088401C00B26D49088064486B38D5 +:1031200090F87F0000EB80006849B1F900108842F8 +:1031300006DA5548407818B900205349487008709D +:1031400062480088401C00B2604908805D48B0F9C0 +:10315000060057496B39B1F87A1088426ADA0020C4 +:103160005C490880488088805B49088048805B48CB +:103170000078401C594900E0E5E208705148B0F978 +:1031800004004B496B39B1F87A1088421CDA4D487B +:10319000B0F9020046496B39B1F87A10884213DA67 +:1031A0003948407880B94D48007814280BD14FF445 +:1031B0007A70334908804FF48070FDF7E3FF0028F0 +:1031C00001D002F09EFB93E10420FDF7DBFF80B30A +:1031D0002D48407868BB3B48B0F9040034496B394E +:1031E000B1F87A10884234DA3648B0F90200304932 +:1031F0006B39B1F87C1088422BDD3248B0F9000001 +:103200002B496B39B1F87C10884222DD33480078B5 +:103210001428D8D13248008830B1002030490880C5 +:1032200001203049088063E12F48008818B9012047 +:1032300002E00EE0C6E000202B4908800846008826 +:1032400018B102202949087052E10320274908706B +:103250004EE117486B38B0F8560000285BDD244873 +:10326000407938B10848007820B1012006494870FB +:10327000204841E045E000006C010020F6010020FC +:10328000F801002000100140FC0400202C01002067 +:103290006801002020A1070070010020E00100204B +:1032A000F04902000C08014070050020AE0100202A +:1032B00017040020740100204C010020AC04002001 +:1032C000EC0400203C010020940100203801002083 +:1032D0003A010020880100208E01002075010020A5 +:1032E0005E01002060010020F20100202801002082 +:1032F0002E0500200E020020B0F90000F9490880D8 +:1033000005E0F948407810B10020F74948700020E6 +:10331000F6490870ECE0F648B0F90400F549B1F858 +:103320007A1088420CDBF34890F87E00012812D115 +:10333000EF48B0F90000EF49B1F87A1088420ADA94 +:10334000E948407838B1E94800781428E2D10020F3 +:10335000E5494870CCE0E648B0F90400E549B1F829 +:103360007C1088420CDCE248B0F90000E149B1F879 +:103370007C10884222DDDF4890F87E0001281DD1B4 +:10338000DB48B0F90200DB49B1F87C10884215DA5D +:10339000D548407890B9D848008878B9D248C078E4 +:1033A00060B1D2480078142807D10120CE49487076 +:1033B000D248B0F90000CB49088099E00020CB4901 +:1033C000087095E0CA48B0F90600CA49B1F87C1007 +:1033D000884220DDC448407800281CD1C448B0F998 +:1033E0000400C449B1F87A10884215DAC048B0F92F +:1033F0000200C049B1F87A1088420DDABB48007863 +:10340000142803D14FF4C870BD490880B74800782C +:10341000401CB64908706BE0B548B0F90400B549E6 +:10342000B1F87C10884214DDB148B0F90200B1490E +:10343000B1F87A1088420CDAAC480078142802D12E +:103440000120A9498873A9480078401CA749087041 +:103450004EE0A748B0F90200A649B1F87C108842B6 +:103460000BDDA448B0F84000801C01B2A148A0F8D0 +:1034700040100120FDF7F2FC3AE09D48B0F902004F +:103480009C49B1F87A1088420BDA9A48B0F84000AB +:10349000801E01B29748A0F840100120FDF7DEFC25 +:1034A00026E09348B0F900009249B1F87C108842B8 +:1034B00009DD9048C08F801C00B28E49C88701206A +:1034C000FDF7CCFC14E08A48B0F900008949B1F856 +:1034D0007A10884209DA8748C08F801E00B2854979 +:1034E000C8870120FDF7BAFC02E000207F49087080 +:1034F0000420FDF747FE10B38248008898B17A484F +:10350000407880B17A48B0F906007A49B1F87A106B +:10351000884208DD7C48407928B932207B49088000 +:103520000020784908807848007A48B178480088B7 +:1035300028B97848008810B93220744908800BE017 +:103540007448008840B16848407828B90020714923 +:10355000088001207049088000253BE0281D64494F +:1035600031F9100040F21451884201DA012000E0E4 +:10357000002005EB45018840291D5D4A32F91110F4 +:1035800040F21452914209DD291D594A32F91110B5 +:1035900040F2A462914201DA012100E0002105EB32 +:1035A0004502521C91400843291D514A32F911101D +:1035B00040F2A462914201DD012100E0002105EB0F +:1035C0004502921C914008430799084380B2079036 +:1035D000681CC5B2042DC1DB00250EE045484C3007 +:1035E00030F8150007990840002801DD012000E0AF +:1035F000002045494855681CC5B20E2DEEDB4248F7 +:10360000007848B93B4890F87F0000EB80004349C0 +:10361000B1F9001088420EDA0120FDF79BFD50B190 +:103620003148007950B900203D4908804880012088 +:103630002D49087102E000202B4908713248407979 +:1036400010B90120284908702748007920B14FF4AB +:1036500000403449086004E04FF400403149091F3C +:1036600008601020FDF776FD88B31F48C07A70B35C +:103670002D48007805282EDB2348807968B11A4848 +:10368000C07968B901201849C8712849081F02F09B +:1036900074F902202649087002E000201249C8711E +:1036A0001948C079A0B11048007A80B901200E49AC +:1036B000087220480068204908601E484068486039 +:1036C000091D081F02F059F901201949087002E08C +:1036D0000020054908720C48007A78B3012002499D +:1036E00088724FE0AA010020FC0400207501002030 +:1036F0003C010020AC030020F80100200E02002055 +:10370000F6010020F20100202E0500205C010020BF +:10371000620100205E0100206001002038010020CD +:103720008E01002014080140E0010020D401002097 +:103730005A010020C8010020D8010020FFE7002026 +:10374000FE4988721EE0FE4991F900000978491C83 +:1037500049B2FB4A1170C11700EB91718910B0EBAF +:10376000810106D0012905D0022904D0032904D102 +:1037700002E006E005E004E003E00020F049087004 +:1037800000BF00BF03F0C9F8EE49086008460068B2 +:10379000ED49096888427DD9EC480089E949096802 +:1037A0000844E9490860FDF788FE03F0B6F8E549EA +:1037B000086008460068E6490968401AE54908803B +:1037C000E0480068E24908601020FDF7C3FC0028CB +:1037D0000AD0DA48C07910B9D848007A10B1D74871 +:1037E000007B10B902F0A6F810E1DB48B0F9000048 +:1037F00004F03BFFD949039004F0C1FE049005F0AA +:10380000B7FB0690D448B0F9000004F02EFFD3496E +:10381000039004F0B4FE049005F0EAFA0590CB485A +:1038200090F8AF00B8B3CE49B1F90210CD4AB2F961 +:103830000220881A01F010F9C44991F8AF104942EA +:10384000884204DAC14890F8AF0040421AE0C44907 +:10385000B1F90210C34AB2F90220881A01F0FCF84B +:10386000BA4991F8AF10884203DDB84890F8AF002C +:1038700008E0BB49B1F90210BA4AB2F90220881A2D +:1038800001F0EAF8B7494988084401B2B5484180D7 +:10389000B34901E0FDE176E0B1F900100246B2F96A +:1038A0000020881A01F0D8F8A84991F8AF104942D1 +:1038B000884204DAA54890F8AF0040421AE0A849CF +:1038C000B1F90010A74AB2F90020881A01F0C4F833 +:1038D0009E4991F8AF10884203DD9C4890F8AF00F4 +:1038E00008E09F49B1F900109E4AB2F90020881AF9 +:1038F00001F0B2F89B490988084401B29948018057 +:103900000146B1F9000004F0B0FE0090069904F001 +:1039100036FE94490290B1F9020004F0A6FE009030 +:10392000059904F02CFE0190029904F022FE8E49C4 +:10393000039004F05AFE049004F0A5FE00B28B49F7 +:1039400008808849B1F9000004F08FFE00900599C5 +:1039500004F015FE83490290B1F9020004F085FEDF +:103960000090069904F00BFE0190029904F0AFFD5F +:103970007D49039004F039FE049004F084FE00B207 +:103980007A49488041E07649B1F9000004F06DFEC3 +:103990000090069904F0F3FD71490290B1F902001C +:1039A00004F063FE0090059904F0E9FD019002998E +:1039B00004F0DFFD6C49039004F017FE049004F05E +:1039C00062FE00B2694908806549B1F9000004F05F +:1039D0004CFE0090059904F0D2FD61490290B1F9C6 +:1039E000020004F042FE0090069904F0C8FD019028 +:1039F000029904F06CFD5C49039004F0F6FD04901C +:103A000004F041FE01B25948418000BF002437E173 +:103A10004A480079F0B3022C77DA554830F914009F +:103A2000524931F91410C1EB400010F5FA7F01DA68 +:103A3000504815E04E4830F914004C4931F9141043 +:103A4000C1EB4000B0F5FA7F02DD4FF4FA7007E0F9 +:103A5000474830F91400454931F91410C1EB4000D2 +:103A6000454931F81410411A38483E3030F81400F6 +:103A7000084406B23548407C7043642190FBF1F065 +:103A800007B2324890F82500404200EB8000B8426F +:103A900008DD00E039E02D4890F82500404200EBB9 +:103AA00080000DE0294890F8250000EB8000B84226 +:103AB00005DA264890F8250000EB800000E0384643 +:103AC00007462E4830F9140030442D49884201DA67 +:103AD00008460DE0294830F91400304442F21071D4 +:103AE000884201DD084603E0244830F914003044E0 +:103AF00000B2224921F81400084630F91400134995 +:103B0000C97E48430013089078E0194830F9140042 +:103B100000EB800001010D480A30005D91FBF0F8D8 +:103B2000184830F81400A8EB00000FFA80F810488D +:103B300030F91470144830F9140027E0FC04002018 +:103B4000A00100202C0100209C010020AC030020DB +:103B500030010020340100200E02002035FA8E3C96 +:103B6000EA010020EE010020000020415201002067 +:103B7000B00100200CFEFFFFCC0000208E010020D1 +:103B8000F0D8FFFFC000002088010020404410F55D +:103B90007A5F01DA40480DE0404830F914004044B3 +:103BA000B0F57A5F02DD4FF47A5003E03B4830F91C +:103BB0001400404400B2394921F81400384830F963 +:103BC0001400002803DD364830F9140003E03448BF +:103BD00030F914004042B0F5207F03DD00202F496A +:103BE00021F814002D4830F914007D2190FBF1F0EC +:103BF0002C49095D4843801100B20890284931F9E9 +:103C00001410294A125D51430A2291FBF2F0C117A8 +:103C100000EB5171A7EBE1010FB2214830F814001D +:103C2000224931F81410401A0FFA80F91C4830F874 +:103C300014001E4921F814001D4830F814001D49D5 +:103C400031F81410084448440FFA80FA184830F844 +:103C50001400184921F81400154820F8149016484B +:103C6000005D00FB0AF040110FFA80FB0898384411 +:103C7000A0EB0B0000B2114921F81400601CC4B283 +:103C8000032CFFF6C5AEFDF793FEFDF73EFEFDF7F4 +:103C900068FE09B0BDE8F08F80C1FFFF88010020F9 +:103CA000C0000020C0030020B801002076010020E1 +:103CB0007C01002082010020BE010020C201002002 +:103CC00010B5F149F14803F0CBF810BD2DE9F047EC +:103CD0000446EF4991F8680004F0D0FC8046204685 +:103CE00004F0CCFC8146EB4904F049FC0746EA4964 +:103CF00004F07BFC0646414604F041FC054604F016 +:103D0000DBFC80B2BDE8F08770B50025002406E03A +:103D100003F060F905440A2002F024FE641C202C04 +:103D2000F6D3C5F34F10FFF7D1FF0546022407E095 +:103D3000D74890F869006043A84200D902E0641CAB +:103D4000062CF5D300BFD5490C70D14890F86A0015 +:103D50006043D349088070BD10B5D2480088002860 +:103D600051DD00241CE0CF480088B0F5C87F03D1A6 +:103D70000020CD4941F82400CB4850F82400CB491D +:103D800031F914100844C84941F824000020C749FB +:103D900021F814000021BE48303020F81410641CB3 +:103DA000032CE0DBBF480088012827D1BE4800680B +:103DB0004FF4C87190FBF1F000B2B5490886BA48DB +:103DC00040684FF4C87190FBF1F001B2B0484186F1 +:103DD000B54880684FF4C87190FBF1F0B449098888 +:103DE000401A01B2AA4881860020A949C88700214B +:103DF000A748A0F840100120FDF730F8A948008836 +:103E0000401EA84908800420FDF7BCF900287DD099 +:103E1000A8480088322811D19D48008EA649088004 +:103E20009B48408E48809A48808E88809848C08FF2 +:103E3000A24908809648B0F8400048809D48008814 +:103E4000002846DD00241BE09A480088322803D170 +:103E500000209B4941F82400994850F824009349D8 +:103E600031F914100844964941F8240000208F4984 +:103E700021F8140000218648303020F81410641C0A +:103E8000032CE1DB8B48008801281DD100208D49DF +:103E9000088001208C49088002208C4908708648DF +:103EA00000887B4908868448418879484186824851 +:103EB000818877488186814800887549C8877F480E +:103EC00041887348A0F840107A480088401E79491C +:103ED00008807F480088012829D100207C4908807B +:103EE00077480068322190FBF1F000B268490886FB +:103EF00073484068322190FBF1F001B2644841867A +:103F00006F488068322190FBF1F000E00FE06849D3 +:103F10000988401A01B25E48818600205C49C88742 +:103F200000215B48A0F840100120FCF797FF5F4894 +:103F300000885749098E401A00B25C49088008463B +:103F400041885348408E081A00B2584948800846B4 +:103F500081884F48808E081A00B25449888010BD6D +:103F600010B54A48416851488847484881684F48D9 +:103F70008847FFF7F1FE10BD10B5564800880028AD +:103F800037DD00242EE053480088B0F57A7F03D156 +:103F90000020514941F824004F4850F824004F496F +:103FA00031F9141008444C4941F8240000204B49D1 +:103FB00021F814004A4921F81400464800880128D5 +:103FC0000FD1454850F824004FF47A7190FBF1F07E +:103FD00000B2434921F8140001220F210A20FEF704 +:103FE00027FD641C032CCEDB3A480088401E39496B +:103FF0000880002438E0394830F81400384931F896 +:104000001410401A00B2354921F81400084630F95E +:104010001410344830F91400A0F54870814205DAD4 +:10402000304830F91400A0F5487012E02B4830F900 +:1040300014102C4830F9140000F54870814205DD59 +:10404000284830F9140000F5487002E0234830F9A0 +:10405000140000B2214921F81400084630F8140079 +:10406000204921F81400641C032CC4DB10BD10B5DA +:1040700005484168194888470348816817488847B8 +:10408000FFF77AFF10BD00007005002060050020DA +:10409000AC0300203333534000F07F45640100201F +:1040A000F4010020F60100203C050020F200002071 +:1040B000FA0100205C010020FE0100200402002023 +:1040C00048050020620100205E0100202801002038 +:1040D00060010020F801002054050020EC000020C1 +:1040E000C60000200802002010B50446FE490C70EE +:1040F0000846007802F00DFEFC480078FA4909787D +:104100004840FA490870200AF749087008460078C4 +:1041100002F0FFFDF5480078F34909784840F3497B +:104120000870200CF04908700846007802F0F1FD94 +:10413000EE480078EC4909784840EC490870200EB8 +:10414000E94908700846007802F0E3FDE748007886 +:10415000E54909784840E549087010BD10B50446A6 +:10416000E3490C700846007802F0D3FDDF48007880 +:10417000DF4909784840DD490870200ADC490870A9 +:104180000846007802F0C5FDD8480078D84909787B +:104190004840D649087010BD10B50446204602F0CC +:1041A000B8FDD24800786040D049087010BDD148B1 +:1041B00001780078401CCF4A1070CF48405C7047AF +:1041C00000B5FFF7F4FF0346FFF7F1FF03EB002014 +:1041D00083B2184600BD10B5FFF7F2FF0446FFF7A3 +:1041E000EFFF04EB0044204610BD70B504460D46B9 +:1041F0002420FFF7D1FF4D20FFF7CEFF0CB1212186 +:1042000000E03E210846FFF7C7FF0020B7490870CD +:104210002846FFF7C1FFB9480078FFF7BDFF70BD22 +:1042200010B5044621460020FFF7DFFF10BD10B592 +:10423000044621460120FFF7D8FF10BD10B5AB485A +:104240000078FFF7A9FF10BD70B505462C4603E0C6 +:104250002078FFF7A1FF641C20780028F8D170BDFA +:1042600010B50446204602F090FC10BD2DE9F04147 +:10427000A2480078732879D00DDCA0F164000F28E3 +:1042800075D2DFE800F0BED1FDFCFBFAF9F8F7F6D5 +:10429000F5F4F3F2F100CC287DD010DCC8281DD055 +:1042A00006DC742874D0752873D076285FD166E256 +:1042B000C92822D0CA2842D0CB28F7D159E0D0282B +:1042C00068D006DCCD287DD0CE287CD0CF28EDD19B +:1042D00093E0FA2878D0FE28E8D19AE2002406E09C +:1042E000FFF76EFF00B2864921F81400641C082C09 +:1042F000F6D30020FFF794FF9DE2FFF758FF8149B6 +:10430000C872FFF754FF80490870FFF764FF7F49C8 +:104310000860FFF760FF7D494860FFF751FF7C4967 +:104320000880FFF74DFF7B4908807B48007840F00C +:104330000200794908700020FFF772FF7BE2002439 +:104340000EE0FFF734FF75490855FFF730FF73495A +:104350000A310855FFF72BFF704914310855641CCA +:104360000A2CEED30020FFF75BFF64E2FAE15EE285 +:1043700011E0002406E0FFF723FF6849423121F8ED +:104380001400641C0E2CF6D30020FFF749FF52E204 +:10439000D3E1D9E120E2FFF70AFF60490A3981F849 +:1043A0002800FFF704FF5D490A3981F82900FFF76B +:1043B000FEFE5A490A3981F82C00FFF7F8FE5749EA +:1043C0000A3902E00FE216E21CE281F82D00FFF745 +:1043D000EEFE52490A3981F82E00FFF7E8FE4F49F8 +:1043E0000A3981F82A00FFF7E2FE4C490A3981F8C0 +:1043F0002B000020FFF714FF1DE20020FFF710FF45 +:1044000019E20720FFF70CFFD220FFF7C5FE434952 +:104410000A394878FFF7C0FE0020FFF7BDFE4FF0D5 +:104420000040FFF761FE06E20A20FFF7F9FE3C4874 +:10443000008800B2FFF792FE02F03FFA06B2304663 +:10444000FFF78CFE0120FCF785FE07460220FCF7F3 +:1044500081FE47EA40070420FCF77CFE47EA80071C +:104460001020FCF777FE0CE075E156E13DE115E127 +:1044700009E100E1E7E0D2E0B3E0A4E095E086E006 +:1044800063E047EAC0070820FCF764FE47EA00162D +:104490003046FFF763FE1B4909791A4A927941EACF +:1044A0004201184A527941EA8201164A527841EA99 +:1044B00042111C4AD27841EAC2011A4A127941EAF1 +:1044C0000211104AD27941EA82110E4A127A41EA67 +:1044D000C2110C4A527A41EA42210A4A927A41EACE +:1044E0000221104A927A1FE01402002019020020D3 +:1044F000150200201A020020800500201B02002067 +:104500003C010020FC040020E0010020C801002044 +:10451000E6010020E801002050010020B603002041 +:10452000340100202E05002041EA8221FE4AD27A81 +:1045300041EAC221FC4A127B41EA0231FA4A527B2B +:1045400041EA4230FFF7D0FD75E11220FFF768FE27 +:10455000002405E0F54931F91400FFF7FFFD641C64 +:10456000032CF7D3002405E0F14931F91400FFF7DB +:10457000F5FD641C032CF7D3002405E0ED4931F967 +:104580001400FFF7EBFD641C032CF7D353E110205C +:10459000FFF746FE002405E0E74931F91400FFF774 +:1045A000DDFD641C082CF7D345E11020FFF738FE31 +:1045B000002405E0E14931F91400FFF7CFFD641C48 +:1045C000082CF7D337E11020FFF72AFE002405E07E +:1045D000DB4931F91400FFF7C1FD641C082CF7D347 +:1045E00029E10E20FFF71CFED649C87AFFF7D4FD5B +:1045F000D5480078FFF7D0FDD4490868FFF774FD6F +:10460000D2494868FFF770FDD148008800B2FFF733 +:10461000A5FDD048008800B2FFF7A0FD0BE1052002 +:10462000FFF7FEFDCC48008800B2FFF797FDCB48AE +:10463000B0F90000FFF792FDC949097801F00100C7 +:10464000FFF7AAFDF7E00820FFF7EAFD002405E0E8 +:10465000C44931F91400FFF781FD641C022CF7D323 +:10466000C148B0F90000FFF779FDC048B0F900007B +:10467000FFF774FDDFE00420FFF7D2FDBC480068BF +:10468000FFF732FDD7E00320FFF7CAFDB9480078F5 +:10469000FFF782FD0020FFF761FDCCE00720FFF768 +:1046A000BFFDB54991F82800FFF776FDB24991F8B2 +:1046B0002900FFF771FDB04991F82C00FFF76CFD60 +:1046C000AD4991F82D00FFF767FDAB4991F82E0039 +:1046D000FFF762FDA84991F82A00FFF75DFDA649A2 +:1046E00091F82B00FFF758FDA5E01E20FFF798FD7D +:1046F00000240FE0A0490A31085DFFF74DFD9E49F7 +:104700001431085DFFF748FD9B491E31085DFFF736 +:1047100043FD641C0A2CEDD38DE01C20FFF780FDC7 +:10472000002407E094494C3131F8141008B2FFF727 +:1047300015FD641C0E2CF5D37DE06320FFF770FDA2 +:104740008E48FFF781FD76E02F20FFF769FD8C484A +:10475000FFF77AFD6FE00220FFF762FD0020FFF710 +:10476000FDFC68E00820FFF75BFD002404E0601C0E +:10477000C0B2FFF711FD641C082CF8D35BE0FFF713 +:1047800016FD05460C20FFF74BFD8DB90020FFF705 +:1047900003FD7C490868FFF7A7FC7A494868FFF7E2 +:1047A000A3FC0020FFF7DAFC0020FFF7F5FC12E085 +:1047B000102D10D11020FFF7EFFC73490868FFF7A8 +:1047C00093FC71494868FFF78FFC0020FFF7C6FC97 +:1047D0000020FFF7E1FC2EE00120FCF774FB002035 +:1047E000FFF71EFD27E04FF4C870684908800020DD +:1047F000FFF716FD1FE00120524988730020FFF7E4 +:104800000FFD18E00020FCF729FB0020FFF708FD52 +:1048100011E00820FFF704FD002405E05C4931F9B0 +:104820001400FFF79BFC641C042CF7D303E000206A +:10483000FFF7FDFC00BF00BFFFF700FDBDE8F08102 +:1048400010B50446232C02D0522C07D102E0FCF70D +:1048500064F803E0012002F033F900BF00BF10BD8F +:1048600010B54C48007810B1FCF757F810BDCDE0FA +:1048700002F036FA04464848007870B9242C01D179 +:10488000012000E000204449087008460078002814 +:1048900002D12046FFF7D4FFB7E03F480078012857 +:1048A00007D14D2C01D1022000E000203A490870C8 +:1048B000ABE039480078022807D13C2C01D1032015 +:1048C00000E00020344908709FE033480078032856 +:1048D0001AD1402C03DD00202F49087096E02F48A4 +:1048E000047000202E4908702E4908702E49087067 +:1048F0002C48007860402B49087004202649087035 +:1049000001202A49087080E023480078042851D10A +:104910002748047023480078604022490870052029 +:104920001D49087071E000002E050020F8000020ED +:10493000C0000020FE000020160100208C04002092 +:104940003C010020FC040020E0010020C801002000 +:10495000E6010020E8010020E2010020E40100203F +:1049600050010020CC0000200E020020AA010020EF +:104970000C010020AC010020AC0300200D970008C2 +:1049800071970008D0010020D8010020F601002016 +:10499000A2010020130200201802002017020020AC +:1049A00016020020190200201A0200201202002024 +:1049B0001B02002021480078052813D120480078E8 +:1049C0002049097888420DDA1F48007860401E4966 +:1049D00008701B4801780078401C194A10701B4869 +:1049E000445412E01548007805280ED11448007888 +:1049F00014490978884208DB13480078A04201D1A5 +:104A0000FFF734FC00200D49087000BF02F051F997 +:104A100000287FF42DAF0E48007868B902F049F9FC +:104A200050B94FF40060FCF7ADFB28B1094840785D +:104A300010B101F02BFB19E700BF17E718020020A7 +:104A40001602002017020020190200208005002015 +:104A500013020020FC04002044F25061884201DD72 +:104A6000A0EB4100FA49884202DA48F6A041084426 +:104A7000704700B5F7480068F7490968421A1046C0 +:104A8000FFF7EAFF0246002A01DD104600E050422F +:104A900042F21071884201DD012000BD0020FCE7D8 +:104AA000014608687047016070472DE9FE4F0446D3 +:104AB0000E4615461F466168701A03F0D6FD804603 +:104AC000296803F092FD2061A168206903F051FD7F +:104AD000E249029091F8AE0003F0D0FDE049009069 +:104AE00003F04DFD014601904FF07E5003F07DFD37 +:104AF0008346296803F0EBFC82465146286803F0A0 +:104B000074FD8146029903F03AFD8046A16803F0E6 +:104B1000DEFC206166602069A0602169B86803F04E +:104B20002EFD804603F0AFFDBDE8FE8F2DE9F04776 +:104B300004460E4617461D46304603F096FD824653 +:104B4000696803F01CFD8146396803F018FD804652 +:104B5000216803F0BCFC2060E86880F00048404613 +:104B6000216803F0C7FD04D2E86880F000402060AF +:104B700006E0E968206803F0BDFD01D2E868206026 +:104B8000206803F080FDBDE8F0872DE9F041804604 +:104B90000C461546204603F068FD0746296803F0D9 +:104BA000EEFC064603F06FFDBDE8F08148F6A0413B +:104BB000884200DD401A002802DA48F6A041084485 +:104BC00070472DE9F041A3490968A34A1268881A81 +:104BD000FFF742FF002807DD9E4909689E4A1268D8 +:104BE000881AFFF739FF07E09A4909689A4A12685C +:104BF000881AFFF731FF404241F2941188423DDAB2 +:104C000094490968944A1268881A03F02EFD0546F3 +:104C1000944903F0B4FC04469349086803F02EFD60 +:104C20000646204604F0A4F90746314603F0A7FCE7 +:104C3000054603F028FD00B28C4908800846B0F90B +:104C400000008B49884201DA08460BE08748B0F93A +:104C5000000040F6B831884201DD084602E0834892 +:104C6000B0F900007B490968084482490860084699 +:104C70000068FFF79BFF7F49086003E07548006804 +:104C80007C490860BDE8F0812DE9FC470546FFF747 +:104C900098FF7849096842F22832501A03F0E5FC7F +:104CA0000746704903F06BFC0646304604F0A0F856 +:104CB0000190304604F05CF90090002481E06E49D8 +:104CC00031F9140003F0D1FC8146284603F0CDFCF5 +:104CD00082465DF8241003F052FC8046494603F0FA +:104CE00048FC074603F0CFFC00B2644921F81400E9 +:104CF000084630F9140010F57A7F01DA60480BE0BD +:104D00005E4830F91400B0F57A7F02DD4FF47A7016 +:104D100002E05A4830F91400584921F814000A46B4 +:104D200032F9141004EB8402564B03EB8200564A0E +:104D3000FFF72BFF0746514A32F9141004EB8402A7 +:104D4000504B03EB8200504B504AFFF7EFFE0744F5 +:104D50004A4A32F9141004EB84024A4B03EB8200F6 +:104D6000494B4A4AFFF7A1FE384400B2484921F8AE +:104D70001400084630F914003D49884201DA08461B +:104D80000BE0434830F9140040F6B831884201DDA9 +:104D9000084602E03E4830F914003D4921F814006D +:104DA00004EB8401374A02EB8100FFF779FE0746E6 +:104DB00004EB8401374A02EB81003946FFF773FEAA +:104DC000641C022CFFF67BAFBDE8FC8770B504467F +:104DD0000D468DB124480068B4EB500F01D2204637 +:104DE00002E021480068400804B2002C01DD2046A2 +:104DF00000E00020044613E01B480068844201D212 +:104E0000204601E01848006804B21448B0F8B20027 +:104E1000A04201DA204602E01048B0F8B20004B225 +:104E20001D48B0F90000844210DD184801681B4895 +:104E300003F0A5FB064603F026FC17490988084441 +:104E400000B2154908800846B0F90040204670BD00 +:104E5000B0B9FFFF580200205C020020AC03002024 +:104E6000DB0FC940D3023739640200206002002002 +:104E700048F4FFFF900200201C02002044020020A2 +:104E800018FCFFFF50060020F00500203C02002027 +:104E9000EA01002028060020680200200000C84225 +:104EA0002DE9F04700247DE0FA4A52F8241004EB83 +:104EB0008402F94B03EB8200F84AFFF766FE814655 +:104EC000F74830F81400A9EB000000B2F54921F8CA +:104ED00014000A4632F9141004EB8402F24B03EB7F +:104EE0008200F24AFFF751FE0746EE4A32F91420DB +:104EF000E84B53F82430D11804EB8402EA4B03EB5F +:104F00008200EA4BEA4AFFF711FE8046E14A52F876 +:104F1000241004EB8402E44B03EB8200E34BE44AED +:104F2000FFF7C3FD054615F5FA6F01DAE14806E023 +:104F3000B5F5FA6F02DD4FF4FA6000E02846054649 +:104F4000D74830F91400002803DDD54830F91400A3 +:104F500003E0D34830F914004042322800DA00253B +:104F600007EB08004619D448864200DA05E040F60F +:104F7000B830864200DD00E0304600B2CF4921F86B +:104F8000140004EB8401C84A02EB8100FFF788FD9E +:104F9000824604EB8401CA4A02EB81005146FFF7C6 +:104FA00082FD641C022CFFF67FAFBDE8F0872DE97F +:104FB000F04704460D4616461F4629683A68881A87 +:104FC00003F053FB8146BF480168484603F0D7FA17 +:104FD000804603F058FBAF49486020683168401AAA +:104FE000AC490860BDE8F0872DE9FF5F06460F4633 +:104FF000904699460F9CD8F800103268881A03F042 +:1050000034FB0546D9F800103A68881A03F02DFBE6 +:105010008346AC480168584603F0B1FA82465146CF +:10502000504603F0ACFA29460190284603F0A7FA4F +:105030000090019903F04BFA029004F05FF8A24946 +:10504000039003F09CFA834603F036FB0E99086048 +:1050500085F0004B5146584603F0A0FD9B49019056 +:1050600003F08DFA9A49029003F031FA039003F0AD +:105070000AFB20602068002804DA48F6A041206876 +:1050800008442060BDE8FF9F2DE9F0419148007879 +:1050900000284FD0864801684FF07E5003F0A5FAF3 +:1050A00006468D4949688D4A5268881A03F0DDFA30 +:1050B000074684480168384603F061FA05463146E0 +:1050C00003F05DFA044603F0DEFA00B2744948804A +:1050D00081490968814A1268881A03F0C6FA0546B0 +:1050E000314603F04CFA044603F0CDFA00B26C49A5 +:1050F0000880B1F902107A4AB2F90220881800EB50 +:10510000D071491009B2664A51801146B1F90010B8 +:10511000734AB2F90020881800EBD071491009B227 +:105120005F4A1180104640886D49488010460088CB +:10513000088000BF012067490870674840686749D8 +:105140004860654800680860BDE8F0812DE9F041DD +:105150000546284603F089FA0746002103F0CAFAFB +:1051600003D2284603F081FA04E0284603F07DFAD2 +:1051700080F0004006465B4903F001FA04462046F1 +:1051800003F036FE4F490860BDE8F081A0F1300120 +:10519000C8B2092801DDC11FC8B200F00F00704776 +:1051A00030B502460B460020002115E0545C2E2C41 +:1051B00005D1491C03B912E00024CD18545500EB69 +:1051C00080046000545C302C05DB545C392C02DC1C +:1051D000545C303C2044491C545C002CE6D100BF98 +:1051E00030BD2DE9F047804600260027B1464546F0 +:1051F00000E06D1C03F0CCF800682978405C2028A2 +:10520000F7D0444609E01EB106EB86004006060EC4 +:1052100014F8010B30383044C6B2281B0228F2DCE7 +:1052200009E01FB107EB87004006070E14F8010BD9 +:1052300030383844C7B2A542F3D828782E2817D181 +:105240006C1C4FF0000A10E009EB89004FEA40099E +:1052500003F09EF800682178405C202803D114F800 +:10526000010B303881440AF1010ABAF1040FEBDB7B +:105270001D48784309EBC90101EB091100EB8100DE +:105280000621B0FBF1F11948704301EBC010BDE8F5 +:10529000F08700004802002000060020D005002012 +:1052A0001C0200204402002028060020E005002007 +:1052B0003C02002030F8FFFF48F4FFFFEA01002025 +:1052C00050060020400200202C7D8E3FA00CB345EC +:1052D00000A00C4634020020C80100202C0200204F +:1052E0002802002050E0EF3040420F002D31010035 +:1052F00070B504460026242C07D10020FE49087012 +:10530000FE490870FE490870F1E02C2C01D02A2CCF +:1053100077D10020FB49F94A12788854F648007882 +:1053200080BB0020F8490870F6480078472811D162 +:10533000F448407850280DD1F2488078472809D1A8 +:10534000F048C078472805D1EE480079412801D1BE +:1053500001200870EB480078472812D1E9484078CE +:1053600050287ED1E748807852287AD1E548C07825 +:105370004D2876D1E3480079432872D10220E249D2 +:1053800008706EE0FFE7E0480078012854D1DA4861 +:105390000078022805D1DB48FFF723FFDB490860CE +:1053A0005FE0D5480078032809D1D6480078532813 +:1053B00005D1D64800684042D449086051E0CE4843 +:1053C0000078042805D1CF48FFF70BFFCF4948608C +:1053D00047E0C9480078052809D1CA48007857280D +:1053E00005D1CA4840684042C849486039E0C248CF +:1053F000007806280AD1C3480078302802DD012051 +:1054000001E042E00020C249C8722AE0BA480078B0 +:10541000072806D10021BB48FFF7C2FEBD4908702E +:105420001FE0B548007809281BD10021B548FFF7D7 +:10543000B7FEB949088014E0B3480078022810D1BB +:10544000AD48007807280CD10121AE48FFF7A8FE2F +:1054500041F2184148434FF47A71B0FBF1F0AF4983 +:105460000880A5480078401CA34908700020A34983 +:1054700008702A2C03D10120A949087037E0A04800 +:10548000007860409E49087031E00D2C01D00A2C54 +:1054900019D1A348007890B19A490878FFF776FEB1 +:1054A00005462807050E97494878FFF76FFE284400 +:1054B000C5B293480078854200D1012600BF002084 +:1054C0009749087013E08D4800780F2807DA8B4859 +:1054D00001780078401C894A10708A4844549048EA +:1054E000007820B986480078604085490870864871 +:1054F000007810B101208B49087026B182480078ED +:10550000012800D170BD0020FCE72DE9FF410546D0 +:10551000E8B2FFF7EDFE00287ED08348007801282E +:1055200003D100208049087002E001207E49087004 +:105530007748C07A0028EFD07648007805286BDBE2 +:105540007348407810B90020714908737048007B97 +:10555000A8B96F48407890B101206D4908736B4835 +:10556000006872490860694840684860674908688F +:10557000FFF7ECFD6E48B0F900006E4908806E48F8 +:105580000078401C052190FBF1F201FB12006A49F2 +:10559000087000247AE05D4850F82400674941F81B +:1055A0002400084650F82400654990FBF1F0654955 +:1055B00041F82400614850F82410624850F8240053 +:1055C000614A5043A1EBC01042F2107190FBF1F020 +:1055D0005E4921F8140004EB84005D4901EB800072 +:1055E0005549097850F821005A4951F82410081AF1 +:1055F000584941F82400514850F82410514850F8B7 +:1056000024005043A1EBC01004EB8401504A02EB8C +:105610008101494A127800E0FFE041F8220004EBE2 +:1056200084004B4901EB80004349097850F8210080 +:10563000484951F824100844464941F824000846D6 +:1056400050F82400052190FBF1F13E4850F8240069 +:105650003D4A504301EBC0103F4941F824003F4808 +:105660000078012811D1394830F8140001280CDDE8 +:10567000364830F8140040F2E731884205DA3648FF +:1056800050F82400214941F82400641C022C82DBDC +:1056900001F059F932490968471A384602F0EEFF1D +:1056A0000646304902F0A1FF2F49086001F04BF98E +:1056B0002B4908604FF07E512B48006803F010F82A +:1056C00002D22948006801E04FF07E502649086068 +:1056D00002A803A9154B1B1D1A1FCDE900100B4989 +:1056E000091D081FFFF780FC64210398B0FBF1F04F +:1056F0001E49088064213BE035020020360200206C +:1057000037020020C005002039020020C801002017 +:10571000FC040020E0010020E6010020E801002058 +:10572000380200205801002050010020D001002044 +:105730000E020020940200202002002074020020AB +:1057400080969800840200202D3101008C020020F8 +:10575000780600206C0200207C0200205A01002004 +:105760002402002000007A443C020020E2010020D4 +:10577000029890FBF1F000B295490880FFF784FC95 +:105780009448007A18B99348C079002845D09248C7 +:105790009249934B1A1FCDE900109249081FFFF759 +:1057A00023FC904B1A1F8E49081FFFF700FC8E4800 +:1057B00090F90000012802D002282DD102E0FFF765 +:1057C0006FFB29E08949B1F8B41008B20121FFF755 +:1057D000FDFA80464046FFF757FA844890F8B0003B +:1057E00038B183480068642190FBF1F000B2814930 +:1057F00008807E48B0F8AC0078490968884202D237 +:10580000FFF737F938B10120774908707A48B0F9C5 +:1058100000007849088000BF00BFBDE8FF8110B5D7 +:105820007249887B02F02AFF0446744902F0DDFECB +:10583000734908606D49087E02F020FF04466F49F5 +:1058400002F0D3FE6E4948606E48C8606749C87B65 +:1058500002F014FF04466C4902F0C7FE6B49086071 +:105860006249487E02F00AFF0446644902F0BDFE28 +:10587000664948605D4991F8230002F0FFFE044646 +:10588000634902F0B2FE614988605E48C8605749CA +:10589000087C02F0F3FE04465B4902F0A6FE5D4977 +:1058A00008605249887E02F0E9FE0446534902F03E +:1058B0009CFE584948604D4991F8240002F0DEFEF4 +:1058C0000446534902F091FE524988604D48C86031 +:1058D00010BD10B50446FFF7A2FF4F49204601F066 +:1058E00037FA4FF4FA7001F03DF84C48007810B1E7 +:1058F0001020FBF738FC10BD002101604160816081 +:1059000070473448C07AA0B145480078052810DBBC +:105910003448001F0068434908603248001F40684F +:1059200048604148B0F90000334908800120294906 +:105930000873704710B500241CE000203B4921F893 +:1059400014003B4921F8140004EB8401394A02EBAE +:105950008100FFF7D1FF04EB8401374A02EB81009D +:10596000FFF7CAFF04EB8401344A02EB8100FFF722 +:10597000C3FF641C022CE0DB10BD7CB504460D4661 +:105980001749091F20680860286848602068FFF7E9 +:10599000DDFB11481149124B1A1FCDE900101149C6 +:1059A000081FFFF721FB0C480068114908600D4BE8 +:1059B0001A1F0B49081FFFF7FAFA07480068204929 +:1059C00008600A48B0F8B20000B21E4908807CBDE9 +:1059D000E4010020FC0400205802002064020020A2 +:1059E00054020020CC0100205A010020AC0300200A +:1059F0009002002010020020940200200000C84203 +:105A0000D00500200000FA4400002041E0050020FD +:105A100000007A44F00500200B55000858010020D2 +:105A2000E0010020D00100200E02002052010020E1 +:105A3000EA01002000060020280600205006002071 +:105A40005C0200206802002070B50446012046492F +:105A5000087000F062FF054644480068281A44496F +:105A60000860424805600846006841F28831884273 +:105A700002D900203F4908703F493E4A12788C54B1 +:105A80003C4800780F2806D101203C4908700020CE +:105A90003B49088004E037480078401C35490870CD +:105AA00070BD10B5374890F8760030B10320364904 +:105AB000087007203549087005E002203249087057 +:105AC00003203249087032494FF4E13001F040F9C7 +:105AD00010BD2A480078704770B50246274B1B78E6 +:105AE000FBB1032118E04C1E234D2C5D264D2D7873 +:105AF0002C4104F00F03072B0CDA1F4C655C4C1E85 +:105B00001D4E345D214E3678344005EB0424214D82 +:105B100045F823408B1CD9B21029E4DB0023174C35 +:105B20002370072A02DA104B1B781BB9154BB3F808 +:105B3000780018E0134B93F876305BB1114B6B3360 +:105B40009B5C144C54F823304FF4777404EB5303EC +:105B500098B208E00B4B6B339B5C0E4C54F823302F +:105B600003F5777398B270BD990200209C02002063 +:105B7000A0020020A4020020BC0600209802002001 +:105B800038010020AC030020A5020020A60200205E +:105B9000495A0008A006002010B50446A048007825 +:105BA00070B900F0D0FE9F4909683231884207D3AE +:105BB00001209B49087000F0C6FE9A4908601CE06D +:105BC00097480078C8B100F0BEFE964909682144A4 +:105BD000884212D300209249087000F0B4FE914927 +:105BE000086091480078002804DD8F480078401E46 +:105BF0008D49087001208D49087010BD2DE9F843CA +:105C000005460E46174698468DF800508DF80160FF +:105C10008DF802708DF80380854909781DF8010020 +:105C200044280AD04C2806D04D2802D04E2809D14D +:105C300006E0642408E0C82406E04FF4FA6403E0B8 +:105C4000002401E0322400BF00BF79480078032817 +:105C500003DA14B12046FFF79FFF75480078032848 +:105C60000BDB00F070FE001B6E490968884204D906 +:105C700000206F4908706C4908706C480078012852 +:105C800000D06CB96A480078032804DA68480078C4 +:105C9000401C67490870002064490870604908701A +:105CA000BDE8F88310B504466248807A18B1012037 +:105CB0006149087002E000205F4908704FF40070ED +:105CC000FBF760FAB0B35D4890F87F0000EB80000E +:105CD0005B49B1F90010884216DA5A48407898B109 +:105CE000012059490870554890F87F00534991F8B0 +:105CF0008010084400EB80005149B1F9001088423F +:105D000002DA0220504908704C4890F87F0000EBFE +:105D100080004B49B1F90010884205DA49484078C3 +:105D200010B90220484908704548008810B9002081 +:105D3000454908701020FBF70DFA78B13D4880798D +:105D400010B93C48C07930B13E48C07A18B901203A +:105D50003E49087002E000203C4908703A4800784B +:105D6000022806D144234E2211464C20FFF746FF5D +:105D700054E035480078012806D14D234C221946BD +:105D80005320FFF73BFF49E030480078012806D157 +:105D90004D234E2253210846FFF730FF3EE02648B0 +:105DA0000078012806D14D23532211461046FFF7F3 +:105DB00025FF33E0042C06D144234D221146532005 +:105DC000FFF71CFF2AE0022C06D144234D22532169 +:105DD0000846FFF713FF21E0012C06D144234E2291 +:105DE0004D215320FFF70AFF18E0194800780128D9 +:105DF00009D11448407830B14E234D225321084632 +:105E0000FFF7FCFE0AE008480078002803DD322096 +:105E1000FFF7C2FE02E000200149087010BD00003B +:105E2000A8020020B002002028010020A9020020C2 +:105E3000AE0200202E050020AA020020AC030020A4 +:105E400038010020FC040020AC020020AB0200203E +:105E5000AD02002010B504465E2000F05AFF204637 +:105E600000F057FF10BD10B55E2000F052FF10BDCE +:105E700070B50446E5B2284600F04BFFC4F3072591 +:105E8000284600F046FF70BD2DE9F04700241FE0D2 +:105E900004F12401C8B2FFF7DDFF9748008802F043 +:105EA000EDFB8046954931F9140002F0DEFB814696 +:105EB000414602F09AFB0746914902F060FB064614 +:105EC00002F0E1FB05B22846FFF7D2FF601CC4B226 +:105ED000032CDDDBBDE8F08710B51020FFF7BAFF1B +:105EE00088480068642190FBF1F004B22046FFF777 +:105EF000BFFF2120FFF7AEFF82480068642190FBBE +:105F0000F1F201FB120004B22046FFF7B1FF10BD11 +:105F100010B50220FFF79EFF7B48B0F900000A2170 +:105F200090FBF1F004B22046FFF7A2FF10BD70B560 +:105F300000F009FD4FF47A71B0FBF1F43C20B4FBA2 +:105F4000F0F03C21B0FBF1F201FB12051720FFF746 +:105F500081FF290208B2FFF78BFF1820FFF77AFFB5 +:105F60003C20B4FBF0F100FB114006B23046FFF7D5 +:105F70007FFF70BD10B51320FFF76CFF634800680A +:105F8000002802DD6148006802E060480068404285 +:105F90005F4990FBF1F004B22046FFF769FF1B2038 +:105FA000FFF758FF59480068002802DD574800688D +:105FB00002E0564800684042554990FBF1F042F239 +:105FC000107190FBF1F201FB120004B22046FFF7C2 +:105FD0004FFF2320FFF73EFF4C490968002901DAF3 +:105FE000532100E04E210846FFF742FF1220FFF741 +:105FF00031FF46484068002802DD4448406802E01E +:10600000424840684042424990FBF1F004B22046C9 +:10601000FFF72EFF1A20FFF71DFF3C4840680028BD +:1060200002DD3A48406802E038484068404238495A +:1060300090FBF1F042F2107190FBF1F201FB1200C3 +:1060400004B22046FFF714FF2220FFF703FF2F4979 +:106050004968002901DA572100E045210846FFF789 +:1060600007FF10BD10B504462A48007884420CD0C2 +:1060700024B14FF41650FEF7F3F804E02649D1F8A6 +:10608000B800FEF7EDF82348047010BD10B500F01D +:106090005AFC22490968401AC8282BD300F053FC47 +:1060A0001E4908601E480078401C1D490870FFF713 +:1060B000EBFEFFF711FFFFF72BFFFFF7D4FE1848A9 +:1060C0000078052190FBF1F201FB120038B9102095 +:1060D000FBF740F818B1FFF74DFFFFF7C4FE10487B +:1060E0000078192806D100200D490870FFF71FFF1E +:1060F000FFF7B9FE10BD0000FA010020F8000020F3 +:1061000000007A440C010020AE010020C8010020EC +:10611000A0860100B4020020AC030020B8020020D9 +:10612000BC02002038B54FF44060ADF800000220FA +:106130008DF8020014208DF803006946FA4801F03A +:10614000CDFF4FF44061F84802F021F800241CE034 +:1061500002E00A2000F0FAFB4FF48061F24802F0FE +:106160000FF80028F5D04FF48061EF4802F011F8E5 +:106170000A2000F0EBFB4FF48061EB4802F007F8D7 +:106180000A2000F0E3FB601CC4B2082CE0DB4FF4F3 +:106190000061E54801F0FDFF0A2000F0D7FB4FF455 +:1061A0008061E14801F0F5FF0A2000F0CFFB4FF4D9 +:1061B0008061DD4801F0EBFF0A2000F0C7FB4FF4DF +:1061C0000061D94801F0E3FF4FF44060ADF80000F2 +:1061D00002208DF802001C208DF803006946D24889 +:1061E00001F07CFF38BD10B586B004464FF4406026 +:1061F000ADF8100002208DF812001C208DF813005D +:1062000004A9C94801F06AFFC8480460FFF78AFF83 +:10621000C648006801F00EFB684601F076FB0022DC +:106220004FF44071C148006801F0A5FB0020ADF8B3 +:1062300004004BF6FF70ADF806004FF48040ADF857 +:106240000C00BB4800900121B848006801F06BFBCE +:106250006946B648006801F000FB4FF4A06001F009 +:106260006FF922208DF8140000208DF815008DF8AC +:10627000160001208DF8170005A801F066F921200D +:106280008DF8140000208DF8150005A801F05DF9C7 +:1062900006B010BD70B5A5480068848A00BF14F42C +:1062A000E06F3CD0A1480068058B00224FF480616C +:1062B0009E48006801F05FFB14F4007F2FD19B48DB +:1062C0000068008810F4007F29D198480068008891 +:1062D00010F4807F17D000BF94480068008810F445 +:1062E000807FF9D101219148006801F030FB00BFA7 +:1062F0008E480068008810F4007FF9D18B48006850 +:10630000FFF771FF0BE001218848006801F01FFBD7 +:1063100000224FF440718548006801F02CFB83484F +:106320000068808A20F470608049096888820020B3 +:106330008049087070BD10B5FFF7ACFF10BD70B597 +:106340007A480068808AC4B214F0010F3FD07748C1 +:106350000068008820F40060744909680880012101 +:106360007248006801F0FDFA002073490870734814 +:106370000078E8B17248007818B972480078FF28B0 +:1063800016D101206E4908706F480078022807D1A5 +:1063900066480068008840F4006064490968088025 +:1063A00001226A4801786148006801F0F1FA98E139 +:1063B0000022664801785D48006801F0E9FA61480A +:1063C0000078FF28F3D0FF205B49087089E114F0C2 +:1063D000020F5BD0BFF3508F5B48007801281FD1BC +:1063E00056480078E0B156480078C8B100214F48BF +:1063F000006801F0B6FABFF3508F4C480068008B7C +:10640000C5B201214948006801F0A1FA01205049B4 +:106410000870012281024548006801F0ACFA34E0BE +:1064200042480068008BC5B2BFF3508F46480078E1 +:10643000022812D14148007878B14148007860B113 +:1064400000213A48006801F08CFA00224FF4806184 +:106450003648006801F08FFA17E03B4800780328BF +:106460000DD13648007850B13548007838B1002257 +:106470004FF480612D48006801F07DFA05E00122AB +:1064800091022A48006801F076FA2AE114F0040F1C +:1064900049D001202E4908702848007800287DD076 +:1064A00027480078002879D027480078022831DD75 +:1064B00000211E48006801F054FA1C48006801F0F1 +:1064C00064FA1D4991F900200978491C49B21A4B18 +:1064D000197020490968885401211448006801F0A6 +:1064E00036FA01201A4908701048006801F04DFA88 +:1064F000114991F900200978491C49B20E4B1970D5 +:10650000144909688854012291020848006801F082 +:1065100032FA70E00E480078F0B1012103480068BB +:1065200001F015FA1DE06EE0000C0140C8020020E9 +:10653000801A0600CC020020C5020020D1020020F3 +:10654000C3020020CE020020CF020020CD02002096 +:10655000C4020020D80200200121D948006801F0BF +:10656000ECF9D748006801F010FAD64991F90020FB +:106570000978491C49B2D34B1970D349096888542A +:10658000CF48006801F001FACE4991F9002009785E +:10659000491C49B2CB4B1970CB4900E008E00968AF +:1065A000885418460078401C40B21946087022E012 +:1065B000C648007810B9C6480078A0B1C548007830 +:1065C00028B10121BE48006801F0C1F904E00121B1 +:1065D000BB48006801F0B1F9BA480078401C40B2ED +:1065E000B849087007E00121B548006801F0A5F935 +:1065F0000120B649087000BFB1480068008810F457 +:10660000807FF9D16DE014F0400F2BD0AC480068CA +:1066100001F0BBF9AB4991F900200978491C49B256 +:10662000A84B1970A84909688854AB4801781846E6 +:1066300090F90000C01C814206D100224FF4806115 +:106640009F48006801F097F9A34800789D4991F9A7 +:106650000010884245D19B480078401C40B29949BF +:1066600008703EE014F0800F3BD0964890F900008F +:10667000401C1DD0934890F900200078401C40B287 +:10668000904B187095480068815C8D48006801F057 +:106690007AF9914800788B4991F90010884220D10D +:1066A00000224FF480618648006801F064F918E028 +:1066B00084480078401C40B28249087088480178BC +:1066C0007F48006801F05FF98648007810B9824879 +:1066D000007830B900224FF480617948006801F0F9 +:1066E0004AF9784890F900107B480078401C8142B4 +:1066F0000FD10020754908707648007830B100222B +:106700004FF440716E48006801F035F90020764979 +:10671000087070BD10B5FFF712FE10BD10B5FFF781 +:10672000B9FD10BD10B5FFF70AFE10BD2DE9FF47FA +:1067300006460F461546984647F230597006000E39 +:106740006A49087066480770012061490870002096 +:10675000644908706149C1F800D05B49C1F800D0B4 +:106760005D480570012060490870102D03DD002090 +:1067700004B0BDE8F087002405E018F804000DF827 +:106780000400601CC4B2AC42F7DB4D48006880884E +:1067900010F4007F18D14A480068008810F4807F08 +:1067A0000BD100BF46480068008810F4007FF9D183 +:1067B00001214348006801F0C0F801224FF4407104 +:1067C0003F48006801F0D7F800BF4748007820B183 +:1067D000A9F101005FEA0009F7D1B9F1000F0AD170 +:1067E00043480088401C4249088035480068FFF74C +:1067F000FAFC0020BCE70120BAE737B504460D4695 +:1068000002AB012229462046FFF790FF3EBD2DE94D +:10681000F04105460E4617461C4647F230586806BA +:10682000000E324908702E48067000202849087072 +:1068300001202C4908702448046028480460264838 +:1068400007700120284908701D480068808810F4EE +:10685000007F18D11A480068008810F4807F0BD19F +:1068600000BF17480068008810F4007FF9D10121AB +:106870001348006801F061F801224FF4407110489C +:10688000006801F078F800BF1748007820B1A8F13F +:1068900001005FEA0008F7D1B8F1000F0BD11448EE +:1068A0000088401C1249088005480068FFF79BFCDF +:1068B0000020BDE8F0810120FBE70D48008870470B +:1068C000C8020020C5020020D8020020C302002018 +:1068D000D0020020C4020020CF020020D4020020F9 +:1068E000CE020020D1020020CC020020CD020020E8 +:1068F000C002002000B585B0684601F057F8754920 +:106900000098B0FBF1F07449086005B000BD734811 +:106910000068401C71490860704700BF6F480168FB +:106920004FF0E02082696D4800688142F6D16C48E2 +:10693000801A4823B0FBF3F001EB4103C3EBC11312 +:1069400000EBC300704765480068704730B50446E7 +:10695000FFF7E3FF054600BFFFF7DFFF401BA04244 +:10696000FAD330BD10B5044603E04FF47A70FFF758 +:10697000EDFF2000A4F10104F7D110BDF0B585B002 +:10698000584B0FCB8DE80F0002250121564801F02E +:1069900064F8012144F61D2001F056F80121084653 +:1069A00001F049F801F06BF84FF6FF70ADF81000F8 +:1069B00000208DF8130004A94C4801F08FFB04A9B6 +:1069C0004B4801F08BFB04A94A4801F087FB0121E9 +:1069D000494801F0E0FB002414E0684600EBC400E5 +:1069E0008088ADF8100002208DF81200684600EB98 +:1069F000C40080798DF813005DF8340004A901F01B +:106A00006DFB641CAC42E8D34FF4805039490861F7 +:106A1000C000364910310860FFF76CFF3748006846 +:106A20004FF47A72B0FBF2F1B1F1807F00D31DE038 +:106A300021F07F40401E4FF0E022506150170F229E +:106A4000002807DA13071F0E2D4B00F00F06361F24 +:106A50009F5503E013071E0E2A4B1E5400BF002053 +:106A60004FF0E02290610720106100BF00F026FA8D +:106A70006420FFF777FF05B0F0BD04464FF40040F7 +:106A80001A4914310860C0101A49086117E0174804 +:106A90000C30006880F4004014490C31086015483F +:106AA000C06880F480501349C86040F2DB1204FBD8 +:106AB00002F1881EFFF756FF1920FFF753FFE6E7A4 +:106AC00010B11149114A116011490D4A0C3A116077 +:106AD0007047000040420F00DC020020E00200206E +:106AE00040190100A4970008070040000008014079 +:106AF000000C014000100140000230006003002043 +:106B000018ED00E000E400E0EFBEADDEF04F002045 +:106B10000400FA0510B5B848B84909680844B849EE +:106B20000865B8480068B549096888420BD9B54876 +:106B30000068B2490968401AB1498864B1480068E0 +:106B4000AE49086008E0AD480068C0F58070AC4907 +:106B500088640020A94908600121A948443000F058 +:106B600045FE10BD10B54FF4005000F055FE002159 +:106B7000A348443000F03AFEA24800689F490968E3 +:106B8000884201D0FFF7C6FF10BD10B592B0044691 +:106B90004FF40070ADF8440002208DF84600182034 +:106BA0008DF8470011A9984801F098FA4FF48060D9 +:106BB000ADF8440048208DF8470011A9924801F033 +:106BC0008DFA0E208DF8040001208DF805008DF857 +:106BD00006008DF8070001A800F0B7FC0D94002016 +:106BE000ADF83800ADF83A00ADF83C00ADF8400023 +:106BF0000C20ADF83E000DA9844801F0C7F980488B +:106C0000583000F069FD4FF480500B9000200C903C +:106C10007E48001D02907E4803900020049006905C +:106C2000089080200790002009904FF48070059014 +:106C300020200A9002A97248583000F0BAFD0121C4 +:106C40006F48583000F0D2FD012240216F4801F01A +:106C500017FA6B48583000F0DCFD6E490860684850 +:106C6000443000F039FD6948001D02901020049066 +:106C700000200690089080200790002009900A903C +:106C800002A95F48443000F094FD012202215C48D3 +:106C9000443000F0B6FD002059498864012280216B +:106CA0005A4801F0EDF90121584801F0C7F912B036 +:106CB00010BD10B55248583000F0ABFD5549096879 +:106CC000884201D0012010BD0020FCE74B4800683D +:106CD0004C490968884201D1012070470020FCE737 +:106CE0004C490968C1F58071494A505C49490968B5 +:106CF000491E484A116002D14FF4807111607047FB +:106D000010B500BFFFF7D5FF0028FBD0FFF7E8FF65 +:106D100010BD10B5044638483A490968445439480A +:106D20000068401CC0B2374908603548406C10F01C +:106D3000010F01D1FFF7EEFE10BD10B5044603E0D0 +:106D400014F8010BFFF7E5FF20780028F8D110BDFB +:106D500030B587B004460D460121480400F07DFEA1 +:106D600026208DF8180001208DF8190002208DF8DA +:106D70001A0001208DF81B0006A800F0E6FB082091 +:106D8000ADF8140004208DF8170005A91E4801F085 +:106D9000A5F901940020ADF80800ADF80A00ADF89F +:106DA0000C000420ADF80E000020ADF8100001A981 +:106DB000194801F0EBF8012240F22551164801F084 +:106DC00047F90121144801F039F91448056007B06A +:106DD00030BD10B540F225510F4801F05DF9012892 +:106DE00009D10E48006830B10B4801F051F9044652 +:106DF0000A490968884710BDCC070020E802002036 +:106E000000000240EC020020000801400038014070 +:106E1000CC060020E402002000440040F0020020E4 +:106E200070476D490988490009B201806A4949885B +:106E3000490009B2418068498988490009B28180C6 +:106E40007047704770476449C98809B20180624938 +:106E5000098909B241806049498909B28180704736 +:106E60005E4A02605E4A42605E4A82605B4A0A6035 +:106E70005D4A4A605D4A8A604FF4BC725C4B1A807E +:106E8000704770B505460C4615E00520FFF76AFD12 +:106E9000284600F0C0FB00BF284600F0C1FB0028D8 +:106EA000FAD1284600F0C3FB00BF284600F0C4FB1F +:106EB0000028FAD1641E002CE7DC70BD00B591B04B +:106EC0004C4800F009FC4C480190434802900020D7 +:106ED0000390092004900020059080200690400037 +:106EE0000790800008902020099000020A9000205E +:106EF0000B9001A93F4800F05CFC01213D4800F0E7 +:106F000075FC00200C9001208DF834008DF83500C0 +:106F10004FF460200E9000200F9009208DF8400063 +:106F20000CA935484C3800F043FB032301220A2109 +:106F300031484C3800F091FB032302220B212E48EC +:106F40004C3800F08AFB03231A460C212A484C389F +:106F500000F083FB032304220D2127484C3800F066 +:106F60007CFB032305220E2123484C3800F075FBDF +:106F7000032306220F2120484C3800F06EFB032328 +:106F8000072205211C484C3800F067FB0323082228 +:106F9000062119484C3800F060FB03230922072121 +:106FA00015484C3800F059FB012113484C3800F0CB +:106FB00028FB012110484C3800F019FB02210E4833 +:106FC0004C38FFF75EFF01210B484C3800F03BFBCB +:106FD00011B000BD00207047CC080020436E0008AF +:106FE000476E0008456E0008236E0008216E0008F9 +:106FF000FA010020080002404C2401402DE9FC4128 +:107000000646002700256BE0FB4800EBC50103C9DD +:10701000CDE90001F94800EBC5040098B0425DD10C +:10702000BDF80610304600F0A2FF012856D1BDF889 +:107030000610009800F0A6FF15B90120F04908706D +:10704000BDF8040030B1042809D008280CD00C2861 +:1070500014D10EE0009800F081FF07460EE0009882 +:1070600000F07EFF074609E0009800F07BFF07462E +:1070700004E0009800F078FF074600BF00BF2078CA +:1070800008B9678000E0A780207858B901202070F7 +:107090000220DC494880BDF804000880009800F018 +:1070A00085FE1BE0A0886188884204DDA088618895 +:1070B000401AE08006E060884FF6FF71081AA18848 +:1070C0000844E08000202070CF490880CD494880E6 +:1070D000BDF804000880009800F068FE681CC5B286 +:1070E000082D91DBBDE8FC8170B5054602212846DC +:1070F00000F03DFF01280BD1C4480088C449088036 +:10710000284600F02BFFC14908800120BC490870C7 +:107110000221284600F036FFBC480088BC49098897 +:10712000884206DDB9480088B9490988401A84B206 +:1071300008E0B74800884FF6FF71081AB34909887C +:10714000084484B2B4F57A6F03DD0020B1490870B9 +:1071500019E040F2EE2084420DDD40F6CA00844280 +:1071600009DAAC480078082805DAA448A949097862 +:1071700000EBC100C480A7480078401CA5490870F6 +:107180000020A149088070BD10B5A348007820B147 +:107190004FF08040FFF7A8FF03E04FF08040FFF77B +:1071A0002DFF10BD30B585B005460020049001903C +:1071B000029003900090002D46D00120ADF8100001 +:1071C00028208DF8130002208DF8120004A993489E +:1071D00000F084FF1C208DF8000000208DF80100D5 +:1071E00001208DF802008DF80300684600F0ADF92B +:1071F00001A800F073FE4720ADF804004FF6FF70C1 +:10720000ADF808000020ADF8060001A94FF080405D +:1072100000F044FC00207B49488001208880002049 +:10722000C880088108804FF0804000F0BFFD012237 +:107230000221480700F070FE0121880700F057FE88 +:107240000A207749087052E01F20ADF8100028206E +:107250008DF8130002208DF8120004A96F4800F089 +:107260003DFF1C208DF8000000208DF8010001205A +:107270008DF802008DF80300684600F066F901A859 +:1072800000F02CFE4720ADF804004FF6FF70ADF87B +:1072900008000020ADF8060001A94FF0804000F082 +:1072A000FDFB002057494880012088800020C880CD +:1072B000088100240DE0504800EBC400808851494B +:1072C00008804D4951F834004E4900F06FFD601CB4 +:1072D000C4B2042CEFDB01221E21900700F01CFE3B +:1072E0000121880700F003FE04204D49087005B015 +:1072F00030BD30B589B00446002008900590069056 +:1073000007900190029003900490607842490870C1 +:10731000002507E040F2DC50384901EBC501C88088 +:10732000681CC5B2082DF5DB207818B13A48007802 +:10733000FFF738FF4FF47070ADF8200018208DF87B +:10734000230002208DF8220008A9364800F0C6FE6E +:1073500005A800F0C3FD4720ADF81400A08832490D +:1073600091FBF0F0401E80B2ADF8180005A92F483F +:1073700000F094FB7020ADF804000120ADF8060089 +:107380000020ADF808004FF47A70ADF80A00022032 +:10739000ADF80C00C001ADF8100001A9234800F0C1 +:1073A000B6FB01A9214800F0E7FB01A91F4800F046 +:1073B0001DFC01A91D4800F051FC08211B4800F0EC +:1073C000B3FD0821194800F0B5FD0821174800F069 +:1073D000B8FD0821154800F0BAFD0121134800F05E +:1073E00086FD0121114800F08CFD08210F4800F0B6 +:1073F0009BFD002009B030BDF4020020DE08002013 +:10740000560300201E0900203801002058030020E8 +:107410005A0300205C0300205403002000080140B0 +:1074200055030020000C014040420F0000080040BE +:10743000084A1278904203DA074A52F82020118055 +:1074400070470146054800EBC100C08870470148FD +:10745000007870475503002034030020DE08002028 +:10746000324810B5016841F0010101604168304ABD +:107470001140416001682F4A11400160016821F408 +:1074800080210160416821F4FE0141604FF41F0139 +:10749000816000F005F828494FF00060086010BDD9 +:1074A00022480021026842F4803202604FF4A06357 +:1074B000026801F1010112F4003F01D19942F7D1B4 +:1074C0000168890330D51D490A6842F010020A603C +:1074D0000A6822F003020A600A6842F002020A60A7 +:1074E0004168416041684160416841F480614160A8 +:1074F000416821F47C114160416841F4E811416028 +:10750000016841F08071016001688901FCD5416822 +:1075100021F003014160416841F00201416041688E +:10752000C1F381010229FAD1704700000010024026 +:107530000000FFF8FFFFF6FE08ED00E0002002402B +:107540001849084318490860704770B50F21C4787E +:10755000027801234FF0E026DCB1134C246804F4D8 +:10756000E064C4F5E064250AC5F10404E940457807 +:10757000A54084780C402C4321010C4C1155007817 +:1075800000F01F018B40400906EB8000C0F800317D +:1075900070BD02F01F008340500906EB8000C0F868 +:1075A000803170BD0000FA050CED00E000E400E061 +:1075B00010B54268464B0C791A400B6842EA042227 +:1075C000134343608368434A1340D1E90242224394 +:1075D0004C7943EA44031A438260C26A097C22F46C +:1075E0007002491EC9B242EA0151C16210BD0029B0 +:1075F000816802D041F0010101E021F001018160C8 +:1076000070470029816802D041F4807101E021F4C3 +:10761000807181607047816841F008018160704726 +:10762000014600208968090700D50120704781685C +:1076300041F00401816070470146002089684907D4 +:1076400000D5012070470029816802D041F4A001D3 +:1076500001E021F4A0018160704770B50725092978 +:107660000AD9C468A1F10A0606EB4606B540AC4348 +:10767000B3401C43C46007E0046901EB4106B54018 +:10768000AC43B3401C4304611F23072A09D2446B57 +:10769000521E02EB820293409C4391400C43446390 +:1076A00070BD0D2A09D2046BD21F02EB82029340F7 +:1076B0009C4391400C43046370BDC46A0D3A02EBD5 +:1076C000820293409C4391400C43C46270BD000011 +:1076D000FFFEF0FFFDF7F1FF01684FF6FE7211406B +:1076E00001600021016041608160C1604F494F4AE3 +:1076F0000839904203D1486840F00F0006E04B4A39 +:107700001432904204D1486840F0F000486070475D +:10771000464A2832904203D1486840F47060F5E749 +:10772000424A3C32904203D1486840F47040EDE751 +:107730003E4A5032904203D1486840F47020E5E759 +:107740003A4A6432904203D1486840F47000DDE761 +:10775000364A7832904203D1486840F07060D5E7ED +:10776000334A111F904203D1086840F00F0006E031 +:107770002F4A1432904204D1086840F0F0000860AB +:1077800070472B4A2832904203D1086840F4706059 +:10779000F5E7274A3C32904203D1086840F4704034 +:1077A000EDE7234A50329042EAD1086840F4702055 +:1077B000E5E730B5036847F6F07293430C6A8A68D0 +:1077C0002243D1E904452C4322438C692243CC69EE +:1077D00022434C6A22438C6A22431A430260CA68DD +:1077E00042600A6882604968C16030BD0029016852 +:1077F00002D041F0010102E04FF6FE72114001603B +:107800007047002A026801D00A4300E08A43026000 +:107810007047406880B27047C10003D50449091F12 +:107820000860704701490839486070470800024005 +:10783000080402405A4910B588424FF0010101D1B5 +:107840004C0501E04FF48004204600F00FF920467B +:10785000BDE81040002100F009B970B504468088E9 +:1078600086B00D4620F03F06684600F09FF84D496F +:107870000298B0FBF1F189B20E43A680228822F073 +:1078800001022280484B2A689A421CD85200B0FB61 +:10789000F2F080B2042800D20420491C2184A08385 +:1078A000208840F00100208021884FF6F53001400B +:1078B000A8886A89104308432080A8892989084339 +:1078C000208106B070BDEB88A3F53F46FF3E05D191 +:1078D00002EB4202B0FBF2F080B208E002EBC2031E +:1078E00003EB0212B0FBF2F080B240F480400205DC +:1078F00001D140F001004FF4967251434FF47A7277 +:10790000B1FBF2F140F40040C7E741F28831016079 +:10791000002181804BF6FF72C280018141814FF4CA +:107920008041818170470029018802D041F0010126 +:1079300001E021F00101018070470029018802D097 +:1079400041F4807101E021F48071018070470029C9 +:10795000018802D041F4007101E021F4007101803E +:1079600070470029018802D041F4806101E021F4D0 +:10797000806101807047002A828801D00A4300E0BC +:107980008A438280704701827047008AC0B2704784 +:1079900012B141F0010101E001F0FE0101827047E6 +:1079A0000054004040420F00A0860100374910B546 +:1079B0004A6812F00C03364A03D0042B01D0082B7E +:1079C00026D002604A68334B02F0F00212099C5C38 +:1079D0000268E24042604C6804F4E064240A1C5DE2 +:1079E00022FA04F484604C6804F460544FEAD4240E +:1079F0001B5D22FA03F2C2604968264B01F4404144 +:107A00004FEA91311B1F595CB2FBF1F1016110BDCE +:107A10004A684B6802F470124FF0020413F4803F7E +:107A200004EB924202D04B689B0301D51A4B00E055 +:107A3000174B5A43C5E7154A0029516901D0014344 +:107A400000E0814351617047104A0029916901D0DB +:107A5000014300E08143916170470C4A0029D169DC +:107A600001D0014300E08143D1617047074A0029FA +:107A7000116901D0014300E081431161704703485F +:107A8000416A41F08071416270470000001002407D +:107A900000127A007803002000093D0030B502880A +:107AA000F84BF94C98420DD0A0420BD0B0F1804F6A +:107AB00008D0F64DA84205D0F54DA84202D0F54DAC +:107AC000A84203D122F070054A882A43F24DA84209 +:107AD00006D0F24DA84203D022F44075CA882A434A +:107AE00002808A8882850A88028598420AD0A0424C +:107AF00008D0EB4A904205D0EA4A904202D0EA4AC6 +:107B0000904201D1097A01860121818230BD30B5D0 +:107B1000028C22F001020284028C8388048B22F002 +:107B2000020224F073050C882C430D8915434A8802 +:107B30002A43D44DA8420BD0D34DA84208D0D84DEB +:107B4000A84205D0D74DA84202D0D74DA8420DD1AA +:107B500022F008054A8923F440732A4322F00405E1 +:107B60008A882A438D891D43CB892B4383800483D4 +:107B7000C9888186028430BD30B5028C22F01002A3 +:107B80000284028C8388048B22F0200224F4E645D0 +:107B90000C88240645EA14440D892D0542EA154552 +:107BA0004A88120545EA1242B64DA84202D0B64DA7 +:107BB000A84215D122F080054A8923F440631205BA +:107BC00045EA124222F040058A88120545EA12422F +:107BD0008D89AD0443EA1545CB899B0445EA1343DF +:107BE00083800483C9880187028430BD30B5028C4C +:107BF00022F480720284028C8388848B22F40072C7 +:107C000024F073050C882C430D892D0642EA154596 +:107C10004A88120645EA12429A4DA84202D09A4D6D +:107C2000A84215D122F400654A8923F44053120674 +:107C300045EA124222F480658A88120645EA124219 +:107C40008D892D0543EA1545CB891B0545EA13436C +:107C500083808483C9888187028430BD30B5028CDB +:107C600022F480520284038C8288848B24F4E645BB +:107C70000C88240645EA144423F400550B891B079D +:107C800045EA13434D882D0743EA15457D4B98423D +:107C900002D07D4B984205D122F480438A89920517 +:107CA00043EA124282808483C988A0F84010058488 +:107CB00030BD828B22F440628283828B42EA0122B1 +:107CC00082837047828B22F00C028283828B0A436C +:107CD00082837047028B22F440620283028B42EA65 +:107CE00001220283704770B5048C24F010040484D0 +:107CF000068B048C26F473461B0746EA13431206D0 +:107D000043EA12420D055F4B2D0C98420ED05E4B9C +:107D100098420BD0B0F1804F08D05C4B984205D010 +:107D20005B4B984202D05B4B984205D124F0200176 +:107D3000294341F0100104E024F0A0030B4343F079 +:107D400010010283018470BD028B22F00C020283B9 +:107D5000028B0A430283704730B5048C24F001047F +:107D60000484058B048C1B0542EA134325F0F305BC +:107D7000444A2B4390420ED0434A90420BD0B0F17C +:107D8000804F08D0414A904205D0414A904202D0EB +:107D9000404A904202D124F0020201E024F00A029B +:107DA0000A4342F001010383018430BD2DE9F05FF5 +:107DB0000D4604460E883348DFF8CCC0DFF8CCA06F +:107DC000DFF8CCE04988AA882B894FF0804B3EB37E +:107DD000042E2DD0082E268C32D026F480562684F0 +:107DE000B4F81C90268C0F074FEA1748120629F4A6 +:107DF00073471B0747EA124242EA134384420AD000 +:107E0000644508D05C4506D0544504D0744502D082 +:107E10002048844256D126F4005040EA080054E03D +:107E20002046FFF799FFE9882046BDE8F05F8BE721 +:107E30002046FFF758FFE9882046BDE8F05F49E794 +:107E400026F480762684A78B268C1B0527F0F30763 +:107E500042EA13434FEA01683B434FEA1848844221 +:107E60000AD0644508D05C4506D0544504D074451A +:107E700002D00848844219D126F4007040EA080074 +:107E800017E00000002C01400034014000040040D5 +:107E900000080040000C00400010004000140040AA +:107EA00000400140004401400048014026F42060A9 +:107EB000084340F48070A3832084E9882046BDE80D +:107EC000F05FFFE626F40240084340F48050A383AD +:107ED0002084E9882046BDE8F05FEAE64FF6FF71AE +:107EE000818000210180C18041800172704700299A +:107EF000018802D041F0010101E021F0010101807F +:107F00007047002930F8441F02D041F4004101E0DD +:107F1000C1F30E0101807047002A828901D00A4313 +:107F200000E08A4382817047028B22F008020A43F4 +:107F300002837047028B22F4006242EA012101832E +:107F40007047828B22F008020A4382837047828B3B +:107F500022F4006242EA012181837047808E7047DB +:107F6000008F7047808F7047B0F840007047038AD9 +:107F7000002280890B4200EA010001D000B10122F9 +:107F800010467047C94301827047000030B504466F +:107F9000008A85B00D464CF6FF710840E988014320 +:107FA0002182A1894EF6F3100140A8882A89104346 +:107FB0006A890A431043A081A08A4FF6FF41084016 +:107FC000A9890143A1826846FFF7F0FC4248844238 +:107FD00001D1039800E00298A1890904002900EB6F +:107FE000C00101EB0010296802DA4FEA410101E00B +:107FF0004FEA8101B0FBF1F06422B0FBF2F14FEAED +:1080000001114FEA11136FF018056B4300EB830069 +:10801000A3891D044FF0320306D503EBC000B0FB6B +:10802000F2F000F0070005E003EB0010B0FBF2F007 +:1080300000F00F000843208105B030BD0029818980 +:1080400002D041F4005101E021F4005181817047D8 +:1080500010B5C1F3421301F01F040121A140012B0F +:1080600007D0022B07D01430002A026805D00A433B +:1080700004E00C30F8E71030F6E78A43026010BDE8 +:10808000002A828A01D00A4300E08A438282704734 +:108090008088C0F30800704770B501F01F06012208 +:1080A0000025C1F3421302FA06F4012B0FD0022B74 +:1080B0000FD0838A4FEA11210088234202FA01F28D +:1080C00000EA020001D000B10125284670BD838975 +:1080D000F0E7038AEEE70000003801402DE9F041A7 +:1080E000CB78002503F00F02DB0601D58B781A430D +:1080F0000B884FF00F0813F0FF0F4FF0010C1CD04E +:10810000D0F800400E880CFA05F31E409E4210D1B4 +:10811000AF0008FA07F624EA060602FA07F4344329 +:10812000CE78282E02D0482E02D002E0436100E033 +:1081300003616D1C082DE5D304600B88FF2B1DD94E +:108140004468002505F108060CFA06F30E881E4067 +:108150009E420FD1AF0008FA07F624EA060602FA9B +:1081600007F43443CE78282E00D14361CE78482ED0 +:1081700000D103616D1C082DE4D34460BDE8F0819B +:108180000246002092680A4200D001207047016137 +:10819000704741617047F0B51C4C002801DAE36973 +:1081A00000E06368420D120185B2C0F301579540AB +:1081B000C0F30346032F05D0C2020AD50322B24002 +:1081C000934307E023F07062636823F07063636099 +:1081D00002E0AB4343F0706201B12A43002801DAA8 +:1081E000E261F0BD6260F0BD10B58A0721F00304C2 +:1081F0000649130F21440F228C689A4094438C60E7 +:108200008A68984002438A6010BD00000000014067 +:108210003748364941603749416070473448016901 +:1082200041F080010161704731490420CA68D207DA +:1082300001D001207047CA68520701D5022070475B +:10824000C968C906FBD50320704700B50346FFF790 +:10825000EBFF02E0FFF7E8FF5B1E012803D0002BD5 +:1082600000D1052000BD002BF4D1FAE770B505461A +:108270004FF430263046FFF7E8FF042811D11C4C9C +:10828000206940F0020020616561206940F04000F3 +:1082900020613046FFF7D9FF216941F6FD72114098 +:1082A000216170BDF0B505464FF4005C0E46604696 +:1082B000FFF7CBFF042814D10D4C206940F00100DA +:1082C00020612E806046FFF7C0FF41F6FE7704284C +:1082D00004D1300C68806046FFF7B7FF2169394050 +:1082E0002161F0BD0249C860704700002301674565 +:1082F00000200240AB89EFCD1848194902680060A0 +:108300008A4203D01748804717480047174E4FF05E +:10831000150030601648016821F07061016041026B +:108320000160144C5FF4004020601349134808605A +:10833000134C5FF4805020601249134808601348C2 +:10834000D0F800D040680047FEE7FEE7FEE7FEE712 +:10835000FEE7FEE7FEE7FEE7FEE7FEE7F04F002060 +:10836000EFBEADDE61740008ED0000081810024099 +:10837000040001401408014004080140444444340E +:1083800014100140041001404444434400F0FF1F16 +:108390000048704738980008A0F16101192900D8F9 +:1083A000203870472DE9F05F83460F461546994601 +:1083B0004FF0FF36DDF828A011E0A819441009FBA2 +:1083C000047080460146584652469047002802D025 +:1083D00004DA254603E04046BDE8F09F2646A5EBBB +:1083E00006000128E9DC0020F6E740EA01039B07CC +:1083F00003D009E008C9121F08C0042AFAD203E01A +:1084000011F8013B00F8013B521EF9D27047D2B27D +:1084100001E000F8012B491EFBD270470022F6E76D +:1084200010B504460846114602462046FFF7EFFF06 +:10843000204610BD30B50EE003460A4601E05B1C45 +:10844000521C1C781578AC4201D1002CF7D115F0E4 +:10845000FF0F04D0401C0278002AEDD1002030BD6F +:10846000CAB20178914203D009B1401CF9E700205B +:1084700070470146002000E0401C0A5C002AFBD146 +:1084800070472DE9F041054600200E46904604460F +:1084900000E0641C44450BD2285D00F035F9074626 +:1084A000305D00F031F9381A02D1295D0029F0D190 +:1084B000BDE8F08170B5064600F0A4FA04680546F0 +:1084C0000A220021304600F025F92C6070BDF0B47E +:1084D00080EA0102D20F4300B3EB410F02D2034600 +:1084E000084619464B0042D0C30DDDB2C1F3C75454 +:1084F0002C1B202C35DAC1F3160141F4000502B122 +:108500006D42C4F1200605FA06F125412844B3EB7B +:10851000D05F23D0C2B1012CA0EBC35009DCF0BC6A +:108520004FF0004202EAC35200F50000DBB200F057 +:1085300032B9400000F1807000EBC350A0F18070B0 +:1085400040EAD170490009E0490841EAC071A0EB56 +:10855000C35000F50000400800EBC350F0BC00F031 +:1085600011B95142012303EB4101801AF6E7F0BC37 +:10857000704781F00041AAE780F00040A7E780EA59 +:10858000010210B502F00042400026D04B0023D07B +:108590004FEA106101EB1361C0F35600C3F35603B9 +:1085A00040F4000043F40003A0FB0330A1F17F017D +:1085B0004FEA00401C0401D000F1010050EA1340D2 +:1085C00001D44000491EC3B20C0604EBD010401C7D +:1085D0004008802B02D003E0002010BD20F00100F5 +:1085E000002900DA0020104310BD80EA010202F0E9 +:1085F000004330B430F0004221F0004015D0A0B16B +:10860000C0F3C755C2F3C754C2F31601C0F3160036 +:10861000651B41F4000140F400007D35814201D327 +:108620006D1C00E04900002D02DA30BC00207047CC +:108630004FF400020024814201D3091A1443520866 +:108640004FEA4101F7D151B1814202D14FF00041CF +:1086500005E002D24FF0010101E06FF0010104EBEF +:10866000C55030BC184400F08DB8C10F80EAE070EE +:108670000844CA079623002100F08DB896230022F3 +:10868000114600F088B800F0004220F00040C10D13 +:10869000C0F3160040F400007F2901DA0020704783 +:1086A000962903DCC1F19601C84001E09639884063 +:1086B000002AF4D04042704720F00040C10DC0F3C2 +:1086C000160040F400007F2901DA00207047962947 +:1086D00003DCC1F19601C840704796398840704765 +:1086E000002801DBC0F10040002901DBC1F100419D +:1086F00081427047002801DBC0F10040002901DB06 +:10870000C1F1004188427047A0F14101192900D808 +:10871000203070472DE9F0470F46914680460446C9 +:10872000002614F8015B2DB1FFF732FE0068405DB2 +:10873000C007F6D12B2D02D02D2D18D0641E4A462D +:108740003946204600F0C0F827B13968A14201D16E +:10875000C7F8008071054FF002040BD54042002895 +:1087600003DD00F04FF90460A007BDE8F08746F490 +:108770008066E4E70028F8DA00F044F904606FF05E +:108780000040F2E70029A8BF7047401C490008BF1D +:1087900020F00100704710B4B0FA80FC00FA0CF031 +:1087A00050EA010404BF10BC704749B1CCF1200469 +:1087B00021FA04F411FA0CF118BF012121430843F6 +:1087C000A3EB0C01CB1D0106000A002BBEBF00204D +:1087D00010BC704700EBC35010440029A4BF10BC6C +:1087E0007047401C490008BF20F0010010BC7047D2 +:1087F000420005D0C0F3C7525242914201DC002032 +:10880000704700EBC1507047F0B4002802DCF0BCA8 +:1088100000207047C0F3C751C0F3160040F40000B9 +:10882000CA0701D14000491E3F2202EB6105002228 +:1088300011464FF4000626FA01F31344D41884427B +:1088400001D8001B1A464000491C1729F3DD5100CE +:10885000814202D24FF0FF3100E0002102EBC5500F +:10886000F0BCFFF78FBF10B541000CD0C0F3C7516B +:10887000962908DC7E2909DC06DB410204D000F0E1 +:10888000004040F07E5010BD002010BDC1F19604A4 +:10889000C4F1200100FA01F1E040FFF773FFA040AE +:1088A00010BD0000064C074D06E0E06840F00103F3 +:1088B00094E8070098471034AC42F6D3F7F71AFC57 +:1088C000889D0008A89D00082DE9F05F8246007889 +:1088D00000278B4615460AF10104B946302801D01D +:1088E0009DB113E014F8010B0127782803D0582814 +:1088F00001D045B10AE00DB1102D07D10027102598 +:1089000014F8010B02E0082500E00A250026B04615 +:108910000EE005FB080005FB06F1012701EB104600 +:108920001FFA80F8B6F5803F00D3B94614F8010B62 +:10893000294600F018F80028EBDABBF1000F05D04B +:108940000FB1641E00E05446CBF80040B9F1000FAF +:1089500006D000F057F802210160C81EBDE8F09F64 +:1089600048EA0640FAE73A2800D2303820F02002E0 +:10897000412A01D3A2F13700884201D34FF0FF30E2 +:10898000704770B501EB020410F8015B15F00703A6 +:1089900001D110F8013B2A1106D110F8012B03E098 +:1089A00010F8016B01F8016B5B1EF9D12B0705D4A0 +:1089B0000023521E0FD401F8013BFAE710F8013BE7 +:1089C00002F10202A1EB030303E013F8015B01F8DB +:1089D000015B521EF9D5A142D6D3002070BD4100E3 +:1089E000080218BF04200A0E18BF40F001004FF023 +:1089F0007F4232EA010108BF40F00200012808BFAF +:108A00000520704700487047880300206FF05E0122 +:108A10000807FFF7EDBE00002DE9F04D03461446B0 +:108A20004FF07F400E46B0EB440F04D800160860AC +:108A30001846BDE8F08D4FF0004040EA0421C4F331 +:108A4000C7507838431100F01F00DFF814C1C0F19F +:108A50002002FC445CF823500CEB83038540D3F8E0 +:108A600004C02CFA02F72F439D680CFA00FC25FA8B +:108A700002F8DB6805FA00F023FA02F240EA020588 +:108A80004CEA080CA7FB0123ACFB01C0A5FB01517C +:108A900001EB0C05A94294BF4FF0000C4FF0010C04 +:108AA00081186144BCF1000F02D0814202D903E079 +:108AB000814201D2012000E00020184400F1200290 +:108AC0004FEA92188006CA0C40EA42304F03C6F8BB +:108AD0000080FFF7CAFD82463846FFF7CFFD6FF0F2 +:108AE0001201FFF785FE07462846FFF7C7FD6FF026 +:108AF0002501FFF77DFE834639465046FFF7E7FC28 +:108B00005946FFF7E4FC00F500656FF30B0551468D +:108B10002846FFF72EFD3946FFF72BFD5946FFF794 +:108B20002BFD1049FFF72BFD07460F492846FFF79D +:108B300026FD3946FFF7CBFC07460C492846FFF7D0 +:108B40001EFD3946FFF7C3FC14F0004F08BFBDE817 +:108B5000F08DC8F1805180F000403160BDE8F08DAB +:108B6000E60D0000DB0FC92F22AAFD290000C92F46 +:108B700002E008C8121F08C1002AFAD170477047E6 +:108B8000002001E001C1121F002AFBD17047000044 +:108B90000149086070470000880300202DE9F04774 +:108BA0004FF0684202EB400305460C46B3F1654FB7 +:108BB0003CBF02EB4102B2F1654F3FD34FF07F4221 +:108BC000B2EB400F28BFB2EB410F03D2BDE8F04734 +:108BD000FFF77DBC40EA01035B0008BF44F0FF41A2 +:108BE0000AD0B2EB400F08BFB2EB410F06D125F01F +:108BF000804024F0804105460C461FE0B2EB400F58 +:108C000012BF5FEA410245F0FF4004F0004115D079 +:108C10004FEA410292EA400310D4002AACBF4FF061 +:108C20009F464FF03E563146FFF7A9FC05463146B8 +:108C30002046FFF7A4FC044628462146C0F3C7524D +:108C4000C1F3C753D21A1B2A06DD10F0004F14BF20 +:108C500054485548BDE8F08712F11A0F17DA11F0A1 +:108C6000004F06D010F0004F14BF50485048BDE8E8 +:108C7000F08721462846FFF7B8FC0446FFF7AFFE11 +:108C8000042808BFFFF7C2FE2046BDE8F087420077 +:108C9000B2EB410F25D910F0004F19BF454F464E9A +:108CA000464F474E224685F0004415460A4680F05E +:108CB000004110460A1A5200B2F1807F3ED248406D +:108CC0004049DFF804A110F0004F18D04FF03F48A2 +:108CD0003846FFF74EFC074651463046FFF749FC41 +:108CE00017E011F0004F04BF00263746E2D010F025 +:108CF000004F19BF354F364E364F374EDAE74FF03B +:108D00007C583846FFF7E3FB074651463046FFF7ED +:108D1000DEFB064641462846FFF731FC2146FFF7B9 +:108D2000D6FB824621464046FFF729FC2946FFF73D +:108D300023FC5146FFF759FC044604E0214628462F +:108D4000FFF753FC04460146FFF719FC8046234910 +:108D5000FFF715FC2249FFF7BAFB4146FFF70FFC6E +:108D60002049FFF7B4FB4146FFF709FC1E49FFF716 +:108D7000AEFB4146FFF703FC1C49FFF7A8FB054685 +:108D800041462046FFF7FBFB2946FFF7F8FB31463B +:108D9000FFF79DFB2146FFF79AFB3946BDE8F047F8 +:108DA000FFF795BBDB0FC9BFDB0FC93FDB0F49C026 +:108DB000DB0F49400000C9BF22AAFDB90000C93F2E +:108DC00022AAFD390060ED3EC30ACE37000049C03B +:108DD00022AA7DBA0000494022AA7D3A2DAD65BD88 +:108DE0008FB8D53D0FB511BE61C84C3EA8AAAABE2A +:108DF0002DE9F8430446024650486946B0EB420F5D +:108E000009D94FF0E640B0EB420F8CBF4FF0FF3076 +:108E10000020009034E04A4B22F0004083422BD9DE +:108E200048492046FFF7ABFBFFF71DFD0546FFF75E +:108E30002AFC00F00300009043492846FFF79FFBFF +:108E4000064642492846FFF79AFB0746404928460E +:108E5000FFF795FB80463F492846FFF790FB2146E8 +:108E6000FFF78AFB4146FFF784FB3946FFF781FB9A +:108E70003146FFF77EFB02E01046FFF7CDFD0446CA +:108E8000009D002D18DA6000B0F17F4F3CBF4FF01D +:108E90007E50BDE8F88309D14FF00100FFF778FE5E +:108EA000BDE8F84300210846FFF79FBB2046BDE818 +:108EB000F8430121FFF79CBC214615F0010F08463D +:108EC0001DD0FFF75CFB06462349FFF758FB2349FB +:108ED000FFF752FB3146FFF752FB2149FFF7F7FA44 +:108EE0003146FFF74CFB2146FFF749FB2146FFF7D0 +:108EF000EEFA15F0020F18BFBDE8F8831AE0FFF78D +:108F00003EFB04461749FFF73AFB1749FFF7DFFA24 +:108F10002146FFF734FB1549FFF7D9FA2146FFF741 +:108F20002EFB4FF07E51FFF7D2FA15F0020F08BF6B +:108F3000BDE8F88380F00040BDE8F883B61F927E5C +:108F4000490E494683F9223F1A61342C0020A2338E +:108F500000A0FD390000C93F336D4C39DA82083C6E +:108F6000A0AA2ABEB93AB2BACA9F2A3DDDFFFFBE07 +:108F70002DE9F8430446544822466946B0EB420FB7 +:108F800009D94FF0E640B0EB440F8CBF4FF0FF30F3 +:108F90000020009034E04D4B22F0004083422BD95A +:108FA0004B491046FFF7EBFAFFF75DFC0646FFF76B +:108FB0006AFB00F00300009046493046FFF7DFFAF5 +:108FC000054645493046FFF7DAFA07464349304639 +:108FD000FFF7D5FA804642493046FFF7D0FA2146DE +:108FE000FFF7CAFA4146FFF7C4FA3946FFF7C1FA5C +:108FF0002946FFF7BEFA02E01046FFF70DFD0446D2 +:10900000009D002D1DDA6000B0F17F4F09D220468F +:10901000FFF7E5FC042808BFFFF7F8FC2046BDE891 +:10902000F88308D10120FFF7B3FDBDE8F843002124 +:109030000846FFF7DABA2046BDE8F8430121FFF7FA +:10904000D7BB214615F0010F08461FD0FFF797FA4E +:1090500004462449FFF793FA2349FFF738FA2146DB +:10906000FFF78DFA2149FFF732FA2146FFF787FA19 +:109070004FF07E51FFF72BFA15F0020F08BFBDE845 +:10908000F88300BF80F00040BDE8F883FFF777FA6F +:1090900006461749FFF773FA1649FFF76DFA31468E +:1090A000FFF76DFA1449FFF712FA3146FFF767FA36 +:1090B0002146FFF764FA2146FFF709FA15F0020F7F +:1090C000E0D1BDE8F8830000B61F927E490E494604 +:1090D00083F9223F1A61342C0020A23300A0FD390D +:1090E0000000C93FB93AB2BACA9F2A3DDDFFFFBEB0 +:1090F000336D4C39DA82083CA0AA2ABE70B5054609 +:10910000FFF782FB044620F00040C0F1FF40C00F93 +:1091100008D025F00040C0F1FF40C00F04BF01207F +:10912000FFF736FD204670BD6E9C0008C39C00080A +:10913000990100089C9C0008869D0008E101000838 +:109140003F9A0008169B0008050200080B9C0008C7 +:10915000869D000811030008079C0008109C000869 +:109160005D0300082C9C0008E09C0008E103000857 +:10917000909A0008B39C0008BD010008989C000864 +:10918000F39C0008FD060008919C0008859C0008DF +:1091900015080008C29B0008869D00080F090008FA +:1091A000AC990008000000001F040020000000002F +:1091B00020000000A9990008000000002004002001 +:1091C0000000000064000000FC9A0008000000009D +:1091D0002104002001000000FA000000639900084B +:1091E0000200000024040020B0040000A4060000D7 +:1091F000119A000802000000300400200000000066 +:10920000D00700001D9A0008020000003204002070 +:1092100000000000D0070000B5990008020000001F +:109220003404002000000000D0070000EA9A000883 +:10923000020000002604002000000000D00700000B +:10924000F39A00080200000028040020000000003B +:10925000D0070000579B0008000000002A040020EF +:109260000000000001000000659D000800000000F3 +:109270002B04002000000000C8000000749D0008BE +:10928000000000002C04002000000000C8000000C6 +:10929000FF990008020000002E040020E8030000EF +:1092A000D0070000569A0008020000003604002093 +:1092B00032000000F2010000479A0008020000009E +:1092C0003804002032000000F2010000739A000808 +:1092D0000400000064040020B004000000C201008B +:1092E000839A00080400000054040020B004000029 +:1092F00000C20100529C000800000000220400206F +:109300000000000001000000E699000800000000D5 +:10931000140400200A000000C8000000D3990008CF +:1093200000000000150400200A00000032000000C8 +:10933000C099000800000000160400200A00000088 +:1093400032000000DA9B0008010000003A0400200F +:10935000FFFFFFFF01000000F0990008020000007D +:109360003C04002000000000D0070000B69B00086D +:10937000020000003E04002000000000D0070000B2 +:10938000599D000802000000400400200000000079 +:10939000D0070000619C0008000000004404002089 +:1093A00000000000FF000000649B000801000000B6 +:1093B000420400209CFFFFFF64000000769B000831 +:1093C00001000000430400209CFFFFFF6400000038 +:1093D000959B000802000000460400206400000085 +:1093E000B80B0000389D000802000000480400206F +:1093F00064000000B80B000088990008020000001B +:109400004A04002064000000B80B0000A69B00087E +:10941000020000004C04002064000000B80B0000B3 +:10942000499D0008020000004E0400206400000076 +:10943000B80B0000999900080200000050040020B9 +:1094400064000000B80B0000329A00080000000021 +:10945000EE0300200000000003000000329C000822 +:1094600000000000EF03002000000000FA000000F0 +:10947000959A000802000000F003002000000000A0 +:1094800000010000419C000802000000F2030020DF +:1094900064000000E8030000CA9B0008030000000D +:1094A000E8030020B0B9FFFF50460000F39B00081E +:1094B00000000000BA03002000000000C800000007 +:1094C000D69A000800000000C4030020000000003D +:1094D000C80000007499000800000000CE030020BE +:1094E00000000000C8000000E89B00080000000029 +:1094F000BB03002000000000C8000000CB9A000859 +:1095000000000000C503002000000000C8000000AB +:109510006999000800000000CF030020000000004F +:10952000C8000000FD9B000800000000BC030020F4 +:1095300000000000C8000000E09A000800000000E1 +:10954000C603002000000000C80000007E9900084B +:1095500000000000D003002000000000C800000050 +:10956000779C000802000000580400200000000062 +:10957000D00700009E9A0008000000005C04002054 +:109580000000000001000000879B000802000000AE +:109590005E0400200A000000D00700002A9D000899 +:1095A00002000000600400200A000000D007000054 +:1095B000659A0008000000005B0400200000000025 +:1095C00064000000299A000802000000B403002093 +:1095D000DC05000028230000C39A000800000000FA +:1095E000B703002000000000C8000000BB9A00087C +:1095F00000000000C103002000000000C8000000BF +:10960000B39A000800000000CB0300200000000017 +:10961000C8000000509B000800000000B6030020B6 +:1096200000000000C8000000499B00080000000086 +:10963000C003002000000000C8000000429B00089A +:1096400000000000CA03002000000000C800000065 +:109650001C9D000800000000B8030020000000006E +:10966000C8000000169D000800000000C203002092 +:1096700000000000C8000000109D0008000000006D +:10968000CC03002000000000C8000000AD9C0008D2 +:1096900000000000B903002000000000C800000026 +:1096A000A79C000800000000C30300200000000089 +:1096B000C8000000A19C000800000000CD030020AD +:1096C00000000000C80000003A9B000800000000F5 +:1096D000BD03002000000000C8000000329B00080D +:1096E00000000000C703002000000000C8000000C8 +:1096F0002A9B000800000000D103002000000000A9 +:10970000C8000000414552543132333400414343D4 +:109710003B4241524F3B4D41473B43414D535441E6 +:10972000423B43414D545249473B41524D3B4750C8 +:109730005320484F4D453B47505320484F4C443BE6 +:1097400050415353544852553B4845414446524575 +:10975000453B4245455045523B4C45444D41583BA5 +:109760004C4C49474854533B4845414441444A3B8B +:1097700000524F4C4C3B50495443483B5941573B96 +:10978000414C543B506F733B506F73523B4E61766C +:10979000523B4C4556454C3B4D41473B56454C3B57 +:1097A00000000000001001400010100000080140FF +:1097B0000080100000404040404040404040414157 +:1097C0004141414040404040404040404040404096 +:1097D0004040404040050202020202020202020230 +:1097E000020202020220202020202020202020022D +:1097F00002020202020290909090909010101010BD +:109800001010101010101010101010101010101058 +:1098100002020202020288888888888808080808EC +:1098200008080808080808080808080808080808B8 +:109830000202020240000000B5970008000000008C +:109840006E83F9A22915444ED15727FCC0DD34F5AB +:10985000999562DB4190433CAB6351FE4D505536C8 +:1098600030353000565441494C340059340041449D +:10987000584C3334350048455836005936004F436C +:10988000544F583800414343004641494C534146E8 +:109890004500414952504C414E45004D414700481A +:1098A000454C495F39305F444547004759524F5F47 +:1098B000534D4F4F5448494E47004C45445F524921 +:1098C0004E4700464C59494E475F57494E47004264 +:1098D00049005452490047494D42414C00494E46C7 +:1098E0004C494748545F4143435F43414C0048451E +:1098F0004C495F3132305F4343504D0050504D0072 +:109900005350454B5452554D004241524F00515512 +:10991000414450004D4F544F525F53544F50004FED +:1099200043544F464C41545000534F4E4152004710 +:109930005053005642415400534552564F5F5449CC +:109940004C54004845583658005155414458004F32 +:1099500043544F464C4154580054454C454D455492 +:109960005259006D69647263006770735F706F7342 +:10997000725F64006770735F706F735F640067701D +:10998000735F6E61765F640067696D62616C5F70C2 +:10999000697463685F6D69640067696D62616C5FBB +:1099A000726F6C6C5F6D6964007961776465616486 +:1099B00062616E64006D696E636F6D6D616E6400EF +:1099C000766261746D696E63656C6C766F6C7461E0 +:1099D000676500766261746D617863656C6C766F43 +:1099E0006C7461676500766261747363616C6500B5 +:1099F0007472695F7961775F6D6964646C65006634 +:109A000061696C736166655F7468726F74746C65AC +:109A1000006D696E7468726F74746C65006D617846 +:109A20007468726F74746C65006C6F6F7074696DBC +:109A300065006163635F6861726477617265006687 +:109A400065617475726500736572766F5F70776DAE +:109A50005F72617465006D6F746F725F70776D5FB8 +:109A600072617465006E61765F736C65775F7261B9 +:109A700074650073657269616C5F626175647261BF +:109A80007465006770735F6261756472617465000C +:109A900073617665006779726F5F6C7066006E61E6 +:109AA000765F636F6E74726F6C735F686561646913 +:109AB0006E6700645F706974636800695F706974E1 +:109AC000636800705F7069746368006770735F70CB +:109AD0006F73725F69006770735F706F735F6900A7 +:109AE0006770735F6E61765F69006D696E6368654C +:109AF000636B006D6178636865636B00616C745FB4 +:109B0000686F6C645F7468726F74746C655F6E65A7 +:109B1000757472616C006C697374206F72202D769D +:109B2000616C206F722076616C00645F6C65766595 +:109B30006C00695F6C6576656C00705F6C6576655E +:109B40006C00645F726F6C6C00695F726F6C6C00AC +:109B5000705F726F6C6C0072657461726465645FD3 +:109B600061726D0067696D62616C5F7069746368D2 +:109B70005F6761696E0067696D62616C5F726F6CCF +:109B80006C5F6761696E006E61765F7370656564B6 +:109B90005F6D696E0067696D62616C5F70697463A7 +:109BA000685F6D696E0067696D62616C5F726F6C92 +:109BB0006C5F6D696E007472695F7961775F6D6962 +:109BC0006E0076657273696F6E006D61675F6465C4 +:109BD000636C696E6174696F6E007961775F646947 +:109BE00072656374696F6E006770735F706F737214 +:109BF0005F70006770735F706F735F700067707382 +:109C00005F6E61765F70006D61700068656C7000FA +:109C10006D617070696E67206F6620726320636883 +:109C2000616E6E656C206F72646572006D69786537 +:109C300072006163635F6C70665F666163746F720C +:109C4000006779726F5F636D70665F666163746FE2 +:109C500072007370656B7472756D5F68697265739D +:109C60000067696D62616C5F666C61677300646553 +:109C70006661756C7473006770735F77705F726193 +:109C8000646975730073686F772073797374656D99 +:109C900020737461747573007365740065786974FA +:109CA00000645F616C7400695F616C7400705F6177 +:109CB0006C74007361766520616E64207265626FFA +:109CC0006F7400726573657420746F2064656661DB +:109CD000756C747320616E64207265626F6F7400BE +:109CE0006D69786572206E616D65206F72206C6998 +:109CF0007374006E616D653D76616C7565206F7281 +:109D000020626C616E6B20666F72206C69737400E8 +:109D1000645F79617700695F79617700705F79616D +:109D200077004D4D4138343578006E61765F737041 +:109D30006565645F6D61780067696D62616C5F7015 +:109D4000697463685F6D61780067696D62616C5FFB +:109D5000726F6C6C5F6D6178007472695F796177A6 +:109D60005F6D6178006661696C736166655F6465EB +:109D70006C6179006661696C736166655F6F6666C8 +:109D80005F64656C61790000A89D000800000020F8 +:109D90008C03000082890008889E00088C03002044 +:109DA0009C150000808B00084113D29814080E996E +:109DB0001B0849041ACF0C1AD6041A7B041A76041D +:109DC0001AC3041A6B041A431C1A7E081A1F081AB5 +:109DD0004F041A920C1AEE041A9F041A6404411AD2 +:109DE000FC081A331C2ADD1019081A14041A380446 +:109DF0001AAB101ABA041A2F0C1A89081A29081A51 +:109E00005904411A85101A090C5A9B182924411328 +:109E1000869D1B086E141A5C041A220C81026318BA +:109E20001204CBDC05020116092426210296030246 +:109E3000FB0122403A020812043A040812083A08C8 +:109E400008120C22105A0420190839201908392048 +:109E5000190829201334081B4038041A3C04191926 +:109E60001B4034181A38041A3C041931193CB13B10 +:109E7000A24A6141380C01020304060708090204E2 +:089E8000066D29106914410070 +:04000005080000ED02 +:00000001FF diff --git a/src/baseflight/src/baseflight_startups/startup_stm32f10x_md.s b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md.s new file mode 100644 index 0000000000..af36eeeaf4 --- /dev/null +++ b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md.s @@ -0,0 +1,349 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00001000 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =0x20004FF0 + LDR R1, =0xDEADBEEF + LDR R2, [R0, #0] + STR R0, [R0, #0] ; Invalidate + CMP R2, R1 + BEQ Reboot_Loader + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +RCC_APB2ENR EQU 0x40021018 +GPIO_AFIO_MASK EQU 0x00000009 +GPIOB_CRL EQU 0x40010C00 +GPIOB_BRR EQU 0x40010C14 +AFIO_MAPR EQU 0x40010004 + +Reboot_Loader PROC + EXPORT Reboot_Loader + + ; RCC Enable GPIOB+AFIO + LDR R6, =RCC_APB2ENR + LDR R0, =GPIO_AFIO_MASK + STR R0, [R6] + ; MAPR pt1 + LDR R0, =AFIO_MAPR + LDR R1, [R0] + BIC R1, R1, #0xF000000 + STR R1, [R0] + ; MAPR pt2 + LSLS R1, R0, #9 + STR R1, [R0] + ; BRR + LDR R4, =GPIOB_BRR + MOVS R0, #0x18 + STR R0, [R4] + ; CRL + LDR R1, =GPIOB_CRL + LDR R0, =0x44433444 + STR R0, [R1] + ; Reboot to ROM + LDR R0, =0x1FFFF000 + LDR SP,[R0, #0] + LDR R0,[R0, #4] + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_fy90q.s b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_fy90q.s new file mode 100644 index 0000000000..dd7e1376d8 --- /dev/null +++ b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_fy90q.s @@ -0,0 +1,359 @@ +;******************** (C) COPYRIGHT 2011 STMicroelectronics ******************** +;* File Name : startup_stm32f10x_md.s +;* Author : MCD Application Team +;* Version : V3.5.0 +;* Date : 11-March-2011 +;* Description : STM32F10x Medium Density Devices vector table for MDK-ARM +;* toolchain. +;* This module performs: +;* - Set the initial SP +;* - Set the initial PC == Reset_Handler +;* - Set the vector table entries with the exceptions ISR address +;* - Configure the clock system +;* - Branches to __main in the C library (which eventually +;* calls main()). +;* After Reset the CortexM3 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;* <<< Use Configuration Wizard in Context Menu >>> +;******************************************************************************* +; THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + +; Amount of memory (in bytes) allocated for Stack +; Tailor this value to your application needs +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00001000 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000200 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD WWDG_IRQHandler ; Window Watchdog + DCD PVD_IRQHandler ; PVD through EXTI Line detect + DCD TAMPER_IRQHandler ; Tamper + DCD RTC_IRQHandler ; RTC + DCD FLASH_IRQHandler ; Flash + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line 0 + DCD EXTI1_IRQHandler ; EXTI Line 1 + DCD EXTI2_IRQHandler ; EXTI Line 2 + DCD EXTI3_IRQHandler ; EXTI Line 3 + DCD EXTI4_IRQHandler ; EXTI Line 4 + DCD DMA1_Channel1_IRQHandler ; DMA1 Channel 1 + DCD DMA1_Channel2_IRQHandler ; DMA1 Channel 2 + DCD DMA1_Channel3_IRQHandler ; DMA1 Channel 3 + DCD DMA1_Channel4_IRQHandler ; DMA1 Channel 4 + DCD DMA1_Channel5_IRQHandler ; DMA1 Channel 5 + DCD DMA1_Channel6_IRQHandler ; DMA1 Channel 6 + DCD DMA1_Channel7_IRQHandler ; DMA1 Channel 7 + DCD ADC1_2_IRQHandler ; ADC1_2 + DCD USB_HP_CAN1_TX_IRQHandler ; USB High Priority or CAN1 TX + DCD USB_LP_CAN1_RX0_IRQHandler ; USB Low Priority or CAN1 RX0 + DCD CAN1_RX1_IRQHandler ; CAN1 RX1 + DCD CAN1_SCE_IRQHandler ; CAN1 SCE + DCD EXTI9_5_IRQHandler ; EXTI Line 9..5 + DCD TIM1_BRK_IRQHandler ; TIM1 Break + DCD TIM1_UP_IRQHandler ; TIM1 Update + DCD TIM1_TRG_COM_IRQHandler ; TIM1 Trigger and Commutation + DCD TIM1_CC_IRQHandler ; TIM1 Capture Compare + DCD TIM2_IRQHandler ; TIM2 + DCD TIM3_IRQHandler ; TIM3 + DCD TIM4_IRQHandler ; TIM4 + DCD I2C1_EV_IRQHandler ; I2C1 Event + DCD I2C1_ER_IRQHandler ; I2C1 Error + DCD I2C2_EV_IRQHandler ; I2C2 Event + DCD I2C2_ER_IRQHandler ; I2C2 Error + DCD SPI1_IRQHandler ; SPI1 + DCD SPI2_IRQHandler ; SPI2 + DCD USART1_IRQHandler ; USART1 + DCD USART2_IRQHandler ; USART2 + DCD USART3_IRQHandler ; USART3 + DCD EXTI15_10_IRQHandler ; EXTI Line 15..10 + DCD RTCAlarm_IRQHandler ; RTC Alarm through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup from suspend +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + + AREA |.text|, CODE, READONLY + +; Reset handler +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT __main + IMPORT SystemInit + LDR R0, =0x20004FF0 + LDR R1, =0xDEADBEEF + LDR R2, [R0, #0] + STR R0, [R0, #0] ; Invalidate + CMP R2, R1 + BEQ Reboot_Loader + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + +RCC_APB2ENR EQU 0x40021018 +GPIO_AFIO_MASK EQU 0x00000015 +GPIOA_CRH EQU 0x40010804 +GPIOA_BRR EQU 0x40010814 +GPIOC_CRH EQU 0x40011004 +GPIOC_BRR EQU 0x40011014 +AFIO_MAPR EQU 0x40010004 + +Reboot_Loader PROC + EXPORT Reboot_Loader + + ; RCC Enable GPIOA+C+AFIO + LDR R6, =RCC_APB2ENR + LDR R0, =GPIO_AFIO_MASK + STR R0, [R6] + ; MAPR pt1 + LDR R0, =AFIO_MAPR + LDR R1, [R0] + BIC R1, R1, #0xF000000 + STR R1, [R0] + ; MAPR pt2 + LSLS R1, R0, #9 + STR R1, [R0] + ; GPIO A BRR + LDR R4, =GPIOA_BRR + MOVS R0, #0x8000 + STR R0, [R4] + ; GPIO A CRL + LDR R1, =GPIOA_CRH + LDR R0, =0x34444444 + STR R0, [R1] + ; GPIO C BRR + LDR R4, =GPIOC_BRR + MOVS R0, #0x1000 + STR R0, [R4] + ; GPIO C CRL + LDR R1, =GPIOC_CRH + LDR R0, =0x44434444 + STR R0, [R1] + ; Reboot to ROM + LDR R0, =0x1FFFF000 + LDR SP,[R0, #0] + LDR R0,[R0, #4] + BX R0 + ENDP + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + + EXPORT WWDG_IRQHandler [WEAK] + EXPORT PVD_IRQHandler [WEAK] + EXPORT TAMPER_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT FLASH_IRQHandler [WEAK] + EXPORT RCC_IRQHandler [WEAK] + EXPORT EXTI0_IRQHandler [WEAK] + EXPORT EXTI1_IRQHandler [WEAK] + EXPORT EXTI2_IRQHandler [WEAK] + EXPORT EXTI3_IRQHandler [WEAK] + EXPORT EXTI4_IRQHandler [WEAK] + EXPORT DMA1_Channel1_IRQHandler [WEAK] + EXPORT DMA1_Channel2_IRQHandler [WEAK] + EXPORT DMA1_Channel3_IRQHandler [WEAK] + EXPORT DMA1_Channel4_IRQHandler [WEAK] + EXPORT DMA1_Channel5_IRQHandler [WEAK] + EXPORT DMA1_Channel6_IRQHandler [WEAK] + EXPORT DMA1_Channel7_IRQHandler [WEAK] + EXPORT ADC1_2_IRQHandler [WEAK] + EXPORT USB_HP_CAN1_TX_IRQHandler [WEAK] + EXPORT USB_LP_CAN1_RX0_IRQHandler [WEAK] + EXPORT CAN1_RX1_IRQHandler [WEAK] + EXPORT CAN1_SCE_IRQHandler [WEAK] + EXPORT EXTI9_5_IRQHandler [WEAK] + EXPORT TIM1_BRK_IRQHandler [WEAK] + EXPORT TIM1_UP_IRQHandler [WEAK] + EXPORT TIM1_TRG_COM_IRQHandler [WEAK] + EXPORT TIM1_CC_IRQHandler [WEAK] + EXPORT TIM2_IRQHandler [WEAK] + EXPORT TIM3_IRQHandler [WEAK] + EXPORT TIM4_IRQHandler [WEAK] + EXPORT I2C1_EV_IRQHandler [WEAK] + EXPORT I2C1_ER_IRQHandler [WEAK] + EXPORT I2C2_EV_IRQHandler [WEAK] + EXPORT I2C2_ER_IRQHandler [WEAK] + EXPORT SPI1_IRQHandler [WEAK] + EXPORT SPI2_IRQHandler [WEAK] + EXPORT USART1_IRQHandler [WEAK] + EXPORT USART2_IRQHandler [WEAK] + EXPORT USART3_IRQHandler [WEAK] + EXPORT EXTI15_10_IRQHandler [WEAK] + EXPORT RTCAlarm_IRQHandler [WEAK] + EXPORT USBWakeUp_IRQHandler [WEAK] + +WWDG_IRQHandler +PVD_IRQHandler +TAMPER_IRQHandler +RTC_IRQHandler +FLASH_IRQHandler +RCC_IRQHandler +EXTI0_IRQHandler +EXTI1_IRQHandler +EXTI2_IRQHandler +EXTI3_IRQHandler +EXTI4_IRQHandler +DMA1_Channel1_IRQHandler +DMA1_Channel2_IRQHandler +DMA1_Channel3_IRQHandler +DMA1_Channel4_IRQHandler +DMA1_Channel5_IRQHandler +DMA1_Channel6_IRQHandler +DMA1_Channel7_IRQHandler +ADC1_2_IRQHandler +USB_HP_CAN1_TX_IRQHandler +USB_LP_CAN1_RX0_IRQHandler +CAN1_RX1_IRQHandler +CAN1_SCE_IRQHandler +EXTI9_5_IRQHandler +TIM1_BRK_IRQHandler +TIM1_UP_IRQHandler +TIM1_TRG_COM_IRQHandler +TIM1_CC_IRQHandler +TIM2_IRQHandler +TIM3_IRQHandler +TIM4_IRQHandler +I2C1_EV_IRQHandler +I2C1_ER_IRQHandler +I2C2_EV_IRQHandler +I2C2_ER_IRQHandler +SPI1_IRQHandler +SPI2_IRQHandler +USART1_IRQHandler +USART2_IRQHandler +USART3_IRQHandler +EXTI15_10_IRQHandler +RTCAlarm_IRQHandler +USBWakeUp_IRQHandler + + B . + + ENDP + + ALIGN + +;******************************************************************************* +; User Stack and Heap initialization +;******************************************************************************* + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap + +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + END + +;******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE***** diff --git a/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_gcc.S b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_gcc.S new file mode 100644 index 0000000000..28159cb160 --- /dev/null +++ b/src/baseflight/src/baseflight_startups/startup_stm32f10x_md_gcc.S @@ -0,0 +1,410 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for Atollic toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =0x20004FF0 // HJI - TC bootloader entry on reset mod + ldr r1, =0xDEADBEEF // HJI - TC bootloader entry on reset mod + ldr r2, [r0, #0] // HJI - TC bootloader entry on reset mod + str r0, [r0, #0] // HJI - TC bootloader entry on reset mod + cmp r2, r1 // HJI - TC bootloader entry on reset mod + beq Reboot_Loader // HJI - TC bootloader entry on reset mod + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/* Call the clock system intitialization function.*/ + bl SystemInit +/* Call static constructors */ + bl __libc_init_array +/* Call the application's entry point.*/ + bl main +/* Atollic update, branch LoopForever */ +LoopForever: + b LoopForever + +.equ RCC_APB2ENR, 0x40021018 // HJI - TC bootloader entry on reset mod +.equ GPIO_AFIO_MASK, 0x00000009 // HJI - TC bootloader entry on reset mod +.equ GPIOB_CRL, 0x40010C00 // HJI - TC bootloader entry on reset mod +.equ GPIOB_BRR, 0x40010C14 // HJI - TC bootloader entry on reset mod +.equ AFIO_MAPR, 0x40010004 // HJI - TC bootloader entry on reset mod + +Reboot_Loader: // HJI - TC bootloader entry on reset mod + // RCC Enable GPIOB+AFIO // HJI - TC bootloader entry on reset mod + ldr r6, =RCC_APB2ENR // HJI - TC bootloader entry on reset mod + ldr r0, =GPIO_AFIO_MASK // HJI - TC bootloader entry on reset mod + str R0, [r6]; // HJI - TC bootloader entry on reset mod + + // MAPR pt1 // HJI - TC bootloader entry on reset mod + ldr r0, =AFIO_MAPR // HJI - TC bootloader entry on reset mod + ldr r1, [r0] // HJI - TC bootloader entry on reset mod + bic r1, r1, #0x0F000000 // HJI - TC bootloader entry on reset mod + str r1, [r0] // HJI - TC bootloader entry on reset mod + + // MAPR pt2 // HJI - TC bootloader entry on reset mod + lsls r1, r0, #9 // HJI - TC bootloader entry on reset mod + str r1, [r0] // HJI - TC bootloader entry on reset mod + + // BRR // HJI - TC bootloader entry on reset mod + ldr r4, =GPIOB_BRR // HJI - TC bootloader entry on reset mod + movs r0, #0x18 // HJI - TC bootloader entry on reset mod + str r0, [r4] // HJI - TC bootloader entry on reset mod + + // CRL // HJI - TC bootloader entry on reset mod + ldr r1, =GPIOB_CRL // HJI - TC bootloader entry on reset mod + ldr r0, =0x44433444 // HJI - TC bootloader entry on reset mod + str r0, [r1] // HJI - TC bootloader entry on reset mod + + // Reboot to ROM // HJI - TC bootloader entry on reset mod + ldr r0, =0x1FFFF000 // HJI - TC bootloader entry on reset mod + ldr sp,[r0, #0] // HJI - TC bootloader entry on reset mod + ldr r0,[r0, #4] // HJI - TC bootloader entry on reset mod + bx r0 // HJI - TC bootloader entry on reset mod + +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _estack + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/src/baseflight/src/board.h b/src/baseflight/src/board.h new file mode 100755 index 0000000000..880f55071e --- /dev/null +++ b/src/baseflight/src/board.h @@ -0,0 +1,169 @@ +#pragma once + +// for roundf() +#define __USE_C99_MATH + +#include +#include +#include +#include +#include +#include +#include + +#include "stm32f10x_conf.h" +#include "core_cm3.h" +#include "printf.h" + +#ifndef M_PI +#define M_PI 3.14159265358979323846f +#endif /* M_PI */ + +typedef enum { + SENSOR_ACC = 1 << 0, + SENSOR_BARO = 1 << 1, + SENSOR_MAG = 1 << 2, + SENSOR_SONAR = 1 << 3, + SENSOR_GPS = 1 << 4, +} AvailableSensors; + +// Type of accelerometer used/detected +typedef enum AccelSensors { + ACC_DEFAULT = 0, + ACC_ADXL345 = 1, + ACC_MPU6050 = 2, + ACC_MMA8452 = 3, +} AccelSensors; + +typedef enum { + FEATURE_PPM = 1 << 0, + FEATURE_VBAT = 1 << 1, + FEATURE_INFLIGHT_ACC_CAL = 1 << 2, + FEATURE_SPEKTRUM = 1 << 3, + FEATURE_MOTOR_STOP = 1 << 4, + FEATURE_SERVO_TILT = 1 << 5, + FEATURE_GYRO_SMOOTHING = 1 << 6, + FEATURE_LED_RING = 1 << 7, + FEATURE_GPS = 1 << 8, + FEATURE_FAILSAFE = 1 << 9, + FEATURE_SONAR = 1 << 10, + FEATURE_TELEMETRY = 1 << 11, + FEATURE_POWERMETER = 1 << 12, +} AvailableFeatures; + +typedef enum { + GPS_NMEA = 0, + GPS_UBLOX, + GPS_MTK, +} GPSHardware; + +typedef void (* sensorInitFuncPtr)(void); // sensor init prototype +typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype +typedef int32_t (* baroCalculateFuncPtr)(void); // baro calculation (returns altitude in cm based on static data collected) +typedef void (* uartReceiveCallbackPtr)(uint16_t data); // used by uart2 driver to return frames to app +typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data + +typedef struct sensor_t +{ + sensorInitFuncPtr init; + sensorReadFuncPtr read; + sensorReadFuncPtr align; + sensorReadFuncPtr temperature; +} sensor_t; + +typedef struct baro_t +{ + uint16_t ut_delay; + uint16_t up_delay; + uint16_t repeat_delay; + sensorInitFuncPtr start_ut; + sensorInitFuncPtr get_ut; + sensorInitFuncPtr start_up; + sensorInitFuncPtr get_up; + baroCalculateFuncPtr calculate; +} baro_t; + +#define digitalHi(p, i) { p->BSRR = i; } +#define digitalLo(p, i) { p->BRR = i; } +#define digitalToggle(p, i) { p->ODR ^= i; } + +// Hardware definitions and GPIO + +#ifdef FY90Q + // FY90Q +#define LED0_GPIO GPIOC +#define LED0_PIN GPIO_Pin_12 +#define LED1_GPIO GPIOA +#define LED1_PIN GPIO_Pin_15 + +#define GYRO +#define ACC + +#else + // Afroflight32 +#define LED0_GPIO GPIOB +#define LED0_PIN GPIO_Pin_3 +#define LED1_GPIO GPIOB +#define LED1_PIN GPIO_Pin_4 +#define BEEP_GPIO GPIOA +#define BEEP_PIN GPIO_Pin_12 +#define BARO_GPIO GPIOC +#define BARO_PIN GPIO_Pin_13 + +#define GYRO +#define ACC +#define MAG +#define BARO +#define LEDRING +#define SONAR + +#endif + +// Helpful macros +#define LED0_TOGGLE digitalToggle(LED0_GPIO, LED0_PIN); +#define LED0_OFF digitalHi(LED0_GPIO, LED0_PIN); +#define LED0_ON digitalLo(LED0_GPIO, LED0_PIN); + +#define LED1_TOGGLE digitalToggle(LED1_GPIO, LED1_PIN); +#define LED1_OFF digitalHi(LED1_GPIO, LED1_PIN); +#define LED1_ON digitalLo(LED1_GPIO, LED1_PIN); + +#ifdef BEEP_GPIO +#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN); +#define BEEP_OFF digitalHi(BEEP_GPIO, BEEP_PIN); +#define BEEP_ON digitalLo(BEEP_GPIO, BEEP_PIN); +#else +#define BEEP_TOGGLE ; +#define BEEP_OFF ; +#define BEEP_ON ; +#endif + +#undef SOFT_I2C // enable to test software i2c + +#ifdef FY90Q + // FY90Q +#include "drv_system.h" // timers, delays, etc +#include "drv_adc.h" +#include "drv_i2c.h" +#include "drv_pwm.h" +#include "drv_uart.h" + +#else + // AfroFlight32 +#include "drv_system.h" // timers, delays, etc +#include "drv_adc.h" +#include "drv_adxl345.h" +#include "drv_bmp085.h" +#include "drv_ms5611.h" +#include "drv_hmc5883l.h" +#include "drv_i2c.h" +#include "drv_ledring.h" +#include "drv_mma845x.h" +#include "drv_mpu3050.h" +#include "drv_mpu6050.h" +#include "drv_l3g4200d.h" +#include "drv_pwm.h" +#include "drv_uart.h" +#include "drv_hcsr04.h" + +#endif diff --git a/src/baseflight/src/buzzer.c b/src/baseflight/src/buzzer.c new file mode 100644 index 0000000000..e963ac3f4f --- /dev/null +++ b/src/baseflight/src/buzzer.c @@ -0,0 +1,128 @@ +#include "board.h" +#include "mw.h" + +static uint8_t buzzerIsOn = 0, beepDone = 0; +static uint32_t buzzerLastToggleTime; +static void beep(uint16_t pulse); +static void beep_code(char first, char second, char third, char pause); + +void buzzer(uint8_t warn_vbat) +{ + static uint8_t beeperOnBox; + static uint8_t warn_noGPSfix = 0; + static uint8_t warn_failsafe = 0; + static uint8_t warn_runtime = 0; + + //===================== BeeperOn via rcOptions ===================== + if (rcOptions[BOXBEEPERON]) { // unconditional beeper on via AUXn switch + beeperOnBox = 1; + } else { + beeperOnBox = 0; + } + //===================== Beeps for failsafe ===================== + if (feature(FEATURE_FAILSAFE)) { + if (failsafeCnt > (5 * cfg.failsafe_delay) && f.ARMED) { + warn_failsafe = 1; //set failsafe warning level to 1 while landing + if (failsafeCnt > 5 * (cfg.failsafe_delay + cfg.failsafe_off_delay)) + warn_failsafe = 2; //start "find me" signal after landing + } + if (failsafeCnt > (5 * cfg.failsafe_delay) && !f.ARMED) + warn_failsafe = 2; // tx turned off while motors are off: start "find me" signal + if (failsafeCnt == 0) + warn_failsafe = 0; // turn off alarm if TX is okay + } + + //===================== GPS fix notification handling ===================== + if (sensors(SENSOR_GPS)) { + if ((rcOptions[BOXGPSHOME] || rcOptions[BOXGPSHOLD]) && !f.GPS_FIX) { // if no fix and gps funtion is activated: do warning beeps + warn_noGPSfix = 1; + } else { + warn_noGPSfix = 0; + } + } + + //===================== Priority driven Handling ===================== + // beepcode(length1,length2,length3,pause) + // D: Double, L: Long, M: Middle, S: Short, N: None + if (warn_failsafe == 2) + beep_code('L','N','N','D'); // failsafe "find me" signal + else if (warn_failsafe == 1) + beep_code('S','M','L','M'); // failsafe landing active + else if (warn_noGPSfix == 1) + beep_code('S','S','N','M'); + else if (beeperOnBox == 1) + beep_code('S','S','S','M'); // beeperon + else if (warn_vbat == 4) + beep_code('S','M','M','D'); + else if (warn_vbat == 2) + beep_code('S','S','M','D'); + else if (warn_vbat == 1) + beep_code('S','M','N','D'); + else if (warn_runtime == 1 && f.ARMED) + beep_code('S','S','M','N'); // Runtime warning + else if (toggleBeep > 0) + beep(50); // fast confirmation beep + else { + buzzerIsOn = 0; + BEEP_OFF; + } +} + +void beep_code(char first, char second, char third, char pause) +{ + char patternChar[4]; + uint16_t Duration; + static uint8_t icnt = 0; + + patternChar[0] = first; + patternChar[1] = second; + patternChar[2] = third; + patternChar[3] = pause; + switch(patternChar[icnt]) { + case 'M': + Duration = 100; + break; + case 'L': + Duration = 200; + break; + case 'D': + Duration = 2000; + break; + case 'N': + Duration = 0; + break; + default: + Duration = 50; + break; + } + + if (icnt < 3 && Duration != 0) + beep(Duration); + if (icnt >= 3 && (buzzerLastToggleTime < millis() - Duration)) { + icnt = 0; + toggleBeep = 0; + } + if (beepDone == 1 || Duration == 0) { + if (icnt < 3) + icnt++; + beepDone = 0; + buzzerIsOn = 0; + BEEP_OFF; + } +} + +static void beep(uint16_t pulse) +{ + if (!buzzerIsOn && (millis() >= (buzzerLastToggleTime + 50))) { // Buzzer is off and long pause time is up -> turn it on + buzzerIsOn = 1; + BEEP_ON; + buzzerLastToggleTime = millis(); // save the time the buzer turned on + } else if (buzzerIsOn && (millis() >= buzzerLastToggleTime + pulse)) { // Buzzer is on and time is up -> turn it off + buzzerIsOn = 0; + BEEP_OFF; + buzzerLastToggleTime = millis(); + if (toggleBeep >0) + toggleBeep--; + beepDone = 1; + } +} diff --git a/src/baseflight/src/cli.c b/src/baseflight/src/cli.c new file mode 100644 index 0000000000..0a1e5abcf6 --- /dev/null +++ b/src/baseflight/src/cli.c @@ -0,0 +1,851 @@ +#include "board.h" +#include "mw.h" + +// we unset this on 'exit' +extern uint8_t cliMode; +static void cliCMix(char *cmdline); +static void cliDefaults(char *cmdline); +static void cliExit(char *cmdline); +static void cliFeature(char *cmdline); +static void cliHelp(char *cmdline); +static void cliMap(char *cmdline); +static void cliMixer(char *cmdline); +static void cliSave(char *cmdline); +static void cliSet(char *cmdline); +static void cliStatus(char *cmdline); +static void cliVersion(char *cmdline); + +// from sensors.c +extern uint8_t batteryCellCount; +extern uint8_t accHardware; + +// from config.c RC Channel mapping +extern const char rcChannelLetters[]; + +// buffer +static char cliBuffer[48]; +static uint32_t bufferIndex = 0; + +static float _atof(const char *p); +static char *ftoa(float x, char *floatString); + +// sync this with MultiType enum from mw.h +const char * const mixerNames[] = { + "TRI", "QUADP", "QUADX", "BI", + "GIMBAL", "Y6", "HEX6", + "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX", + "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", "CUSTOM", NULL +}; + +// sync this with AvailableFeatures enum from board.h +const char * const featureNames[] = { + "PPM", "VBAT", "INFLIGHT_ACC_CAL", "SPEKTRUM", "MOTOR_STOP", + "SERVO_TILT", "GYRO_SMOOTHING", "LED_RING", "GPS", + "FAILSAFE", "SONAR", "TELEMETRY", + NULL +}; + +// sync this with AvailableSensors enum from board.h +const char * const sensorNames[] = { + "ACC", "BARO", "MAG", "SONAR", "GPS", NULL +}; + +// +const char * const accNames[] = { + "", "ADXL345", "MPU6050", "MMA845x", NULL +}; + +typedef struct { + char *name; + char *param; + void (*func)(char *cmdline); +} clicmd_t; + +// should be sorted a..z for bsearch() +const clicmd_t cmdTable[] = { + { "cmix", "design custom mixer", cliCMix }, + { "defaults", "reset to defaults and reboot", cliDefaults }, + { "exit", "", cliExit }, + { "feature", "list or -val or val", cliFeature }, + { "help", "", cliHelp }, + { "map", "mapping of rc channel order", cliMap }, + { "mixer", "mixer name or list", cliMixer }, + { "save", "save and reboot", cliSave }, + { "set", "name=value or blank or * for list", cliSet }, + { "status", "show system status", cliStatus }, + { "version", "", cliVersion }, +}; +#define CMD_COUNT (sizeof(cmdTable) / sizeof(cmdTable[0])) + +typedef enum { + VAR_UINT8, + VAR_INT8, + VAR_UINT16, + VAR_INT16, + VAR_UINT32, + VAR_FLOAT +} vartype_e; + +typedef struct { + const char *name; + const uint8_t type; // vartype_e + void *ptr; + const int32_t min; + const int32_t max; +} clivalue_t; + +const clivalue_t valueTable[] = { + { "deadband", VAR_UINT8, &cfg.deadband, 0, 32 }, + { "yawdeadband", VAR_UINT8, &cfg.yawdeadband, 0, 100 }, + { "alt_hold_throttle_neutral", VAR_UINT8, &cfg.alt_hold_throttle_neutral, 1, 250 }, + { "midrc", VAR_UINT16, &cfg.midrc, 1200, 1700 }, + { "minthrottle", VAR_UINT16, &cfg.minthrottle, 0, 2000 }, + { "maxthrottle", VAR_UINT16, &cfg.maxthrottle, 0, 2000 }, + { "mincommand", VAR_UINT16, &cfg.mincommand, 0, 2000 }, + { "mincheck", VAR_UINT16, &cfg.mincheck, 0, 2000 }, + { "maxcheck", VAR_UINT16, &cfg.maxcheck, 0, 2000 }, + { "retarded_arm", VAR_UINT8, &cfg.retarded_arm, 0, 1 }, + { "failsafe_delay", VAR_UINT8, &cfg.failsafe_delay, 0, 200 }, + { "failsafe_off_delay", VAR_UINT8, &cfg.failsafe_off_delay, 0, 200 }, + { "failsafe_throttle", VAR_UINT16, &cfg.failsafe_throttle, 1000, 2000 }, + { "motor_pwm_rate", VAR_UINT16, &cfg.motor_pwm_rate, 50, 498 }, + { "servo_pwm_rate", VAR_UINT16, &cfg.servo_pwm_rate, 50, 498 }, + { "serial_baudrate", VAR_UINT32, &cfg.serial_baudrate, 1200, 115200 }, + { "gps_baudrate", VAR_UINT32, &cfg.gps_baudrate, 1200, 115200 }, + { "spektrum_hires", VAR_UINT8, &cfg.spektrum_hires, 0, 1 }, + { "vbatscale", VAR_UINT8, &cfg.vbatscale, 10, 200 }, + { "vbatmaxcellvoltage", VAR_UINT8, &cfg.vbatmaxcellvoltage, 10, 50 }, + { "vbatmincellvoltage", VAR_UINT8, &cfg.vbatmincellvoltage, 10, 50 }, + { "power_adc_channel", VAR_UINT8, &cfg.power_adc_channel, 0, 9 }, + { "yaw_direction", VAR_INT8, &cfg.yaw_direction, -1, 1 }, + { "tri_yaw_middle", VAR_UINT16, &cfg.tri_yaw_middle, 0, 2000 }, + { "tri_yaw_min", VAR_UINT16, &cfg.tri_yaw_min, 0, 2000 }, + { "tri_yaw_max", VAR_UINT16, &cfg.tri_yaw_max, 0, 2000 }, + { "wing_left_min", VAR_UINT16, &cfg.wing_left_min, 0, 2000 }, + { "wing_left_mid", VAR_UINT16, &cfg.wing_left_mid, 0, 2000 }, + { "wing_left_max", VAR_UINT16, &cfg.wing_left_max, 0, 2000 }, + { "wing_right_min", VAR_UINT16, &cfg.wing_right_min, 0, 2000 }, + { "wing_right_mid", VAR_UINT16, &cfg.wing_right_mid, 0, 2000 }, + { "wing_right_max", VAR_UINT16, &cfg.wing_right_max, 0, 2000 }, + { "pitch_direction_l", VAR_INT8, &cfg.pitch_direction_l, -1, 1 }, + { "pitch_direction_r", VAR_INT8, &cfg.pitch_direction_r, -1, 1 }, + { "roll_direction_l", VAR_INT8, &cfg.roll_direction_l, -1, 1 }, + { "roll_direction_r", VAR_INT8, &cfg.roll_direction_r, -1, 1 }, + { "gimbal_flags", VAR_UINT8, &cfg.gimbal_flags, 0, 255}, + { "gimbal_pitch_gain", VAR_INT8, &cfg.gimbal_pitch_gain, -100, 100 }, + { "gimbal_roll_gain", VAR_INT8, &cfg.gimbal_roll_gain, -100, 100 }, + { "gimbal_pitch_min", VAR_UINT16, &cfg.gimbal_pitch_min, 100, 3000 }, + { "gimbal_pitch_max", VAR_UINT16, &cfg.gimbal_pitch_max, 100, 3000 }, + { "gimbal_pitch_mid", VAR_UINT16, &cfg.gimbal_pitch_mid, 100, 3000 }, + { "gimbal_roll_min", VAR_UINT16, &cfg.gimbal_roll_min, 100, 3000 }, + { "gimbal_roll_max", VAR_UINT16, &cfg.gimbal_roll_max, 100, 3000 }, + { "gimbal_roll_mid", VAR_UINT16, &cfg.gimbal_roll_mid, 100, 3000 }, + { "align_gyro_x", VAR_INT8, &cfg.align[ALIGN_GYRO][0], -3, 3 }, + { "align_gyro_y", VAR_INT8, &cfg.align[ALIGN_GYRO][1], -3, 3 }, + { "align_gyro_z", VAR_INT8, &cfg.align[ALIGN_GYRO][2], -3, 3 }, + { "align_acc_x", VAR_INT8, &cfg.align[ALIGN_ACCEL][0], -3, 3 }, + { "align_acc_y", VAR_INT8, &cfg.align[ALIGN_ACCEL][1], -3, 3 }, + { "align_acc_z", VAR_INT8, &cfg.align[ALIGN_ACCEL][2], -3, 3 }, + { "align_mag_x", VAR_INT8, &cfg.align[ALIGN_MAG][0], -3, 3 }, + { "align_mag_y", VAR_INT8, &cfg.align[ALIGN_MAG][1], -3, 3 }, + { "align_mag_z", VAR_INT8, &cfg.align[ALIGN_MAG][2], -3, 3 }, + { "acc_hardware", VAR_UINT8, &cfg.acc_hardware, 0, 3 }, + { "acc_lpf_factor", VAR_UINT8, &cfg.acc_lpf_factor, 0, 250 }, + { "acc_lpf_for_velocity", VAR_UINT8, &cfg.acc_lpf_for_velocity, 1, 250 }, + { "acc_trim_pitch", VAR_INT16, &cfg.angleTrim[PITCH], -300, 300 }, + { "acc_trim_roll", VAR_INT16, &cfg.angleTrim[ROLL], -300, 300 }, + { "gyro_lpf", VAR_UINT16, &cfg.gyro_lpf, 0, 256 }, + { "gyro_cmpf_factor", VAR_UINT16, &cfg.gyro_cmpf_factor, 100, 1000 }, + { "mpu6050_scale", VAR_UINT8, &cfg.mpu6050_scale, 0, 1 }, + { "baro_tab_size", VAR_UINT8, &cfg.baro_tab_size, 0, BARO_TAB_SIZE_MAX }, + { "baro_noise_lpf", VAR_FLOAT, &cfg.baro_noise_lpf, 0, 1 }, + { "baro_cf", VAR_FLOAT, &cfg.baro_cf, 0, 1 }, + { "moron_threshold", VAR_UINT8, &cfg.moron_threshold, 0, 128 }, + { "mag_declination", VAR_INT16, &cfg.mag_declination, -18000, 18000 }, + { "gps_type", VAR_UINT8, &cfg.gps_type, 0, 3 }, + { "gps_pos_p", VAR_UINT8, &cfg.P8[PIDPOS], 0, 200 }, + { "gps_pos_i", VAR_UINT8, &cfg.I8[PIDPOS], 0, 200 }, + { "gps_pos_d", VAR_UINT8, &cfg.D8[PIDPOS], 0, 200 }, + { "gps_posr_p", VAR_UINT8, &cfg.P8[PIDPOSR], 0, 200 }, + { "gps_posr_i", VAR_UINT8, &cfg.I8[PIDPOSR], 0, 200 }, + { "gps_posr_d", VAR_UINT8, &cfg.D8[PIDPOSR], 0, 200 }, + { "gps_nav_p", VAR_UINT8, &cfg.P8[PIDNAVR], 0, 200 }, + { "gps_nav_i", VAR_UINT8, &cfg.I8[PIDNAVR], 0, 200 }, + { "gps_nav_d", VAR_UINT8, &cfg.D8[PIDNAVR], 0, 200 }, + { "gps_wp_radius", VAR_UINT16, &cfg.gps_wp_radius, 0, 2000 }, + { "nav_controls_heading", VAR_UINT8, &cfg.nav_controls_heading, 0, 1 }, + { "nav_speed_min", VAR_UINT16, &cfg.nav_speed_min, 10, 2000 }, + { "nav_speed_max", VAR_UINT16, &cfg.nav_speed_max, 10, 2000 }, + { "nav_slew_rate", VAR_UINT8, &cfg.nav_slew_rate, 0, 100 }, + { "looptime", VAR_UINT16, &cfg.looptime, 0, 9000 }, + { "p_pitch", VAR_UINT8, &cfg.P8[PITCH], 0, 200 }, + { "i_pitch", VAR_UINT8, &cfg.I8[PITCH], 0, 200 }, + { "d_pitch", VAR_UINT8, &cfg.D8[PITCH], 0, 200 }, + { "p_roll", VAR_UINT8, &cfg.P8[ROLL], 0, 200 }, + { "i_roll", VAR_UINT8, &cfg.I8[ROLL], 0, 200 }, + { "d_roll", VAR_UINT8, &cfg.D8[ROLL], 0, 200 }, + { "p_yaw", VAR_UINT8, &cfg.P8[YAW], 0, 200 }, + { "i_yaw", VAR_UINT8, &cfg.I8[YAW], 0, 200 }, + { "d_yaw", VAR_UINT8, &cfg.D8[YAW], 0, 200 }, + { "p_alt", VAR_UINT8, &cfg.P8[PIDALT], 0, 200 }, + { "i_alt", VAR_UINT8, &cfg.I8[PIDALT], 0, 200 }, + { "d_alt", VAR_UINT8, &cfg.D8[PIDALT], 0, 200 }, + { "p_level", VAR_UINT8, &cfg.P8[PIDLEVEL], 0, 200 }, + { "i_level", VAR_UINT8, &cfg.I8[PIDLEVEL], 0, 200 }, + { "d_level", VAR_UINT8, &cfg.D8[PIDLEVEL], 0, 200 }, +}; + +#define VALUE_COUNT (sizeof(valueTable) / sizeof(valueTable[0])) + +static void cliSetVar(const clivalue_t *var, const int32_t value); +static void cliPrintVar(const clivalue_t *var, uint32_t full); + +#ifndef HAVE_ITOA_FUNCTION + +/* +** The following two functions together make up an itoa() +** implementation. Function i2a() is a 'private' function +** called by the public itoa() function. +** +** itoa() takes three arguments: +** 1) the integer to be converted, +** 2) a pointer to a character conversion buffer, +** 3) the radix for the conversion +** which can range between 2 and 36 inclusive +** range errors on the radix default it to base10 +** Code from http://groups.google.com/group/comp.lang.c/msg/66552ef8b04fe1ab?pli=1 +*/ + +static char *i2a(unsigned i, char *a, unsigned r) +{ + if (i / r > 0) + a = i2a(i / r, a, r); + *a = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ"[i % r]; + return a + 1; +} + +char *itoa(int i, char *a, int r) +{ + if ((r < 2) || (r > 36)) + r = 10; + if (i < 0) { + *a = '-'; + *i2a(-(unsigned)i, a + 1, r) = 0; + } else + *i2a(i, a, r) = 0; + return a; +} + +#endif + +//////////////////////////////////////////////////////////////////////////////// +// String to Float Conversion +/////////////////////////////////////////////////////////////////////////////// +// Simple and fast atof (ascii to float) function. +// +// - Executes about 5x faster than standard MSCRT library atof(). +// - An attractive alternative if the number of calls is in the millions. +// - Assumes input is a proper integer, fraction, or scientific format. +// - Matches library atof() to 15 digits (except at extreme exponents). +// - Follows atof() precedent of essentially no error checking. +// +// 09-May-2009 Tom Van Baak (tvb) www.LeapSecond.com +// +#define white_space(c) ((c) == ' ' || (c) == '\t') +#define valid_digit(c) ((c) >= '0' && (c) <= '9') +static float _atof(const char *p) +{ + int frac = 0; + double sign, value, scale; + + // Skip leading white space, if any. + while (white_space(*p) ) { + p += 1; + } + + // Get sign, if any. + sign = 1.0; + if (*p == '-') { + sign = -1.0; + p += 1; + + } else if (*p == '+') { + p += 1; + } + + // Get digits before decimal point or exponent, if any. + value = 0.0; + while (valid_digit(*p)) { + value = value * 10.0 + (*p - '0'); + p += 1; + } + + // Get digits after decimal point, if any. + if (*p == '.') { + double pow10 = 10.0; + p += 1; + + while (valid_digit(*p)) { + value += (*p - '0') / pow10; + pow10 *= 10.0; + p += 1; + } + } + + // Handle exponent, if any. + scale = 1.0; + if ((*p == 'e') || (*p == 'E')) { + unsigned int expon; + p += 1; + + // Get sign of exponent, if any. + frac = 0; + if (*p == '-') { + frac = 1; + p += 1; + + } else if (*p == '+') { + p += 1; + } + + // Get digits of exponent, if any. + expon = 0; + while (valid_digit(*p)) { + expon = expon * 10 + (*p - '0'); + p += 1; + } + if (expon > 308) expon = 308; + + // Calculate scaling factor. + while (expon >= 50) { scale *= 1E50; expon -= 50; } + while (expon >= 8) { scale *= 1E8; expon -= 8; } + while (expon > 0) { scale *= 10.0; expon -= 1; } + } + + // Return signed and scaled floating point result. + return sign * (frac ? (value / scale) : (value * scale)); +} + +/////////////////////////////////////////////////////////////////////////////// +// FTOA +/////////////////////////////////////////////////////////////////////////////// +static char *ftoa(float x, char *floatString) +{ + int32_t value; + char intString1[12]; + char intString2[12] = { 0, }; + char *decimalPoint = "."; + uint8_t dpLocation; + + if (x > 0) // Rounding for x.xxx display format + x += 0.0005f; + else + x -= 0.0005f; + + value = (int32_t) (x * 1000.0f); // Convert float * 1000 to an integer + + itoa(abs(value), intString1, 10); // Create string from abs of integer value + + if (value >= 0) + intString2[0] = ' '; // Positive number, add a pad space + else + intString2[0] = '-'; // Negative number, add a negative sign + + if (strlen(intString1) == 1) { + intString2[1] = '0'; + intString2[2] = '0'; + intString2[3] = '0'; + strcat(intString2, intString1); + } else if (strlen(intString1) == 2) { + intString2[1] = '0'; + intString2[2] = '0'; + strcat(intString2, intString1); + } else if (strlen(intString1) == 3) { + intString2[1] = '0'; + strcat(intString2, intString1); + } else { + strcat(intString2, intString1); + } + + dpLocation = strlen(intString2) - 3; + + strncpy(floatString, intString2, dpLocation); + floatString[dpLocation] = '\0'; + strcat(floatString, decimalPoint); + strcat(floatString, intString2 + dpLocation); + + return floatString; +} + +static void cliPrompt(void) +{ + uartPrint("\r\n# "); +} + +static int cliCompare(const void *a, const void *b) +{ + const clicmd_t *ca = a, *cb = b; + return strncasecmp(ca->name, cb->name, strlen(cb->name)); +} + +static void cliCMix(char *cmdline) +{ + int i, check = 0; + int num_motors = 0; + uint8_t len; + char buf[16]; + float mixsum[3]; + char *ptr; + + len = strlen(cmdline); + + if (len == 0) { + uartPrint("Custom mixer: \r\nMotor\tThr\tRoll\tPitch\tYaw\r\n"); + for (i = 0; i < MAX_MOTORS; i++) { + if (cfg.customMixer[i].throttle == 0.0f) + break; + mixsum[i] = 0.0f; + num_motors++; + printf("#%d:\t", i + 1); + printf("%s\t", ftoa(cfg.customMixer[i].throttle, buf)); + printf("%s\t", ftoa(cfg.customMixer[i].roll, buf)); + printf("%s\t", ftoa(cfg.customMixer[i].pitch, buf)); + printf("%s\r\n", ftoa(cfg.customMixer[i].yaw, buf)); + } + for (i = 0; i < num_motors; i++) { + mixsum[0] += cfg.customMixer[i].roll; + mixsum[1] += cfg.customMixer[i].pitch; + mixsum[2] += cfg.customMixer[i].yaw; + } + uartPrint("Sanity check:\t"); + for (i = 0; i < 3; i++) + uartPrint(fabs(mixsum[i]) > 0.01f ? "NG\t" : "OK\t"); + uartPrint("\r\n"); + return; + } else if (strncasecmp(cmdline, "load", 4) == 0) { + ptr = strchr(cmdline, ' '); + if (ptr) { + len = strlen(++ptr); + for (i = 0; ; i++) { + if (mixerNames[i] == NULL) { + uartPrint("Invalid mixer type...\r\n"); + break; + } + if (strncasecmp(ptr, mixerNames[i], len) == 0) { + mixerLoadMix(i); + printf("Loaded %s mix...\r\n", mixerNames[i]); + cliCMix(""); + break; + } + } + } + } else { + ptr = cmdline; + i = atoi(ptr); // get motor number + if (--i < MAX_MOTORS) { + ptr = strchr(ptr, ' '); + if (ptr) { + cfg.customMixer[i].throttle = _atof(++ptr); + check++; + } + ptr = strchr(ptr, ' '); + if (ptr) { + cfg.customMixer[i].roll = _atof(++ptr); + check++; + } + ptr = strchr(ptr, ' '); + if (ptr) { + cfg.customMixer[i].pitch = _atof(++ptr); + check++; + } + ptr = strchr(ptr, ' '); + if (ptr) { + cfg.customMixer[i].yaw = _atof(++ptr); + check++; + } + if (check != 4) { + uartPrint("Wrong number of arguments, needs idx thr roll pitch yaw\r\n"); + } else { + cliCMix(""); + } + } else { + printf("Motor number must be between 1 and %d\r\n", MAX_MOTORS); + } + } +} + +static void cliDefaults(char *cmdline) +{ + uartPrint("Resetting to defaults...\r\n"); + checkFirstTime(true); + uartPrint("Rebooting..."); + delay(10); + systemReset(false); +} + +static void cliExit(char *cmdline) +{ + uartPrint("\r\nLeaving CLI mode...\r\n"); + memset(cliBuffer, 0, sizeof(cliBuffer)); + bufferIndex = 0; + cliMode = 0; + // save and reboot... I think this makes the most sense + cliSave(cmdline); +} + +static void cliFeature(char *cmdline) +{ + uint32_t i; + uint32_t len; + uint32_t mask; + + len = strlen(cmdline); + mask = featureMask(); + + if (len == 0) { + uartPrint("Enabled features: "); + for (i = 0; ; i++) { + if (featureNames[i] == NULL) + break; + if (mask & (1 << i)) + printf("%s ", featureNames[i]); + } + uartPrint("\r\n"); + } else if (strncasecmp(cmdline, "list", len) == 0) { + uartPrint("Available features: "); + for (i = 0; ; i++) { + if (featureNames[i] == NULL) + break; + printf("%s ", featureNames[i]); + } + uartPrint("\r\n"); + return; + } else { + bool remove = false; + if (cmdline[0] == '-') { + // remove feature + remove = true; + cmdline++; // skip over - + len--; + } + + for (i = 0; ; i++) { + if (featureNames[i] == NULL) { + uartPrint("Invalid feature name...\r\n"); + break; + } + if (strncasecmp(cmdline, featureNames[i], len) == 0) { + if (remove) { + featureClear(1 << i); + uartPrint("Disabled "); + } else { + featureSet(1 << i); + uartPrint("Enabled "); + } + printf("%s\r\n", featureNames[i]); + break; + } + } + } +} + +static void cliHelp(char *cmdline) +{ + uint32_t i = 0; + + uartPrint("Available commands:\r\n"); + for (i = 0; i < CMD_COUNT; i++) + printf("%s\t%s\r\n", cmdTable[i].name, cmdTable[i].param); +} + +static void cliMap(char *cmdline) +{ + uint32_t len; + uint32_t i; + char out[9]; + + len = strlen(cmdline); + + if (len == 8) { + // uppercase it + for (i = 0; i < 8; i++) + cmdline[i] = toupper(cmdline[i]); + for (i = 0; i < 8; i++) { + if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i])) + continue; + uartPrint("Must be any order of AETR1234\r\n"); + return; + } + parseRcChannels(cmdline); + } + uartPrint("Current assignment: "); + for (i = 0; i < 8; i++) + out[cfg.rcmap[i]] = rcChannelLetters[i]; + out[i] = '\0'; + printf("%s\r\n", out); +} + +static void cliMixer(char *cmdline) +{ + uint8_t i; + uint8_t len; + + len = strlen(cmdline); + + if (len == 0) { + printf("Current mixer: %s\r\n", mixerNames[cfg.mixerConfiguration - 1]); + return; + } else if (strncasecmp(cmdline, "list", len) == 0) { + uartPrint("Available mixers: "); + for (i = 0; ; i++) { + if (mixerNames[i] == NULL) + break; + printf("%s ", mixerNames[i]); + } + uartPrint("\r\n"); + return; + } + + for (i = 0; ; i++) { + if (mixerNames[i] == NULL) { + uartPrint("Invalid mixer type...\r\n"); + break; + } + if (strncasecmp(cmdline, mixerNames[i], len) == 0) { + cfg.mixerConfiguration = i + 1; + printf("Mixer set to %s\r\n", mixerNames[i]); + break; + } + } +} + +static void cliSave(char *cmdline) +{ + uartPrint("Saving..."); + writeParams(0); + uartPrint("\r\nRebooting..."); + delay(10); + systemReset(false); +} + +static void cliPrintVar(const clivalue_t *var, uint32_t full) +{ + int32_t value = 0; + char buf[8]; + + switch (var->type) { + case VAR_UINT8: + value = *(uint8_t *)var->ptr; + break; + + case VAR_INT8: + value = *(int8_t *)var->ptr; + break; + + case VAR_UINT16: + value = *(uint16_t *)var->ptr; + break; + + case VAR_INT16: + value = *(int16_t *)var->ptr; + break; + + case VAR_UINT32: + value = *(uint32_t *)var->ptr; + break; + + case VAR_FLOAT: + printf("%s", ftoa(*(float *)var->ptr, buf)); + if (full) { + printf(" %s", ftoa((float)var->min, buf)); + printf(" %s", ftoa((float)var->max, buf)); + } + return; // return from case for float only + } + printf("%d", value); + if (full) + printf(" %d %d", var->min, var->max); +} + +static void cliSetVar(const clivalue_t *var, const int32_t value) +{ + switch (var->type) { + case VAR_UINT8: + case VAR_INT8: + *(char *)var->ptr = (char)value; + break; + + case VAR_UINT16: + case VAR_INT16: + *(short *)var->ptr = (short)value; + break; + + case VAR_UINT32: + *(int *)var->ptr = (int)value; + break; + + case VAR_FLOAT: + *(float *)var->ptr = *(float *)&value; + break; + } +} + +static void cliSet(char *cmdline) +{ + uint32_t i; + uint32_t len; + const clivalue_t *val; + char *eqptr = NULL; + int32_t value = 0; + float valuef = 0; + + len = strlen(cmdline); + + if (len == 0 || (len == 1 && cmdline[0] == '*')) { + uartPrint("Current settings: \r\n"); + for (i = 0; i < VALUE_COUNT; i++) { + val = &valueTable[i]; + printf("%s = ", valueTable[i].name); + cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui + uartPrint("\r\n"); + } + } else if ((eqptr = strstr(cmdline, "="))) { + // has equal, set var + eqptr++; + len--; + value = atoi(eqptr); + valuef = _atof(eqptr); + for (i = 0; i < VALUE_COUNT; i++) { + val = &valueTable[i]; + if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0) { + if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT? + cliSetVar(val, valueTable[i].type == VAR_FLOAT ? *(uint32_t *)&valuef : value); // this is a silly dirty hack. please fix me later. + printf("%s set to ", valueTable[i].name); + cliPrintVar(val, 0); + } else { + uartPrint("ERR: Value assignment out of range\r\n"); + } + return; + } + } + uartPrint("ERR: Unknown variable name\r\n"); + } +} + +static void cliStatus(char *cmdline) +{ + uint8_t i; + uint32_t mask; + + printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery)\r\n", + millis() / 1000, vbat, batteryCellCount); + mask = sensorsMask(); + + printf("CPU %dMHz, detected sensors: ", (SystemCoreClock / 1000000)); + for (i = 0; ; i++) { + if (sensorNames[i] == NULL) + break; + if (mask & (1 << i)) + printf("%s ", sensorNames[i]); + } + if (sensors(SENSOR_ACC)) + printf("ACCHW: %s", accNames[accHardware]); + uartPrint("\r\n"); + + printf("Cycle Time: %d, I2C Errors: %d\r\n", cycleTime, i2cGetErrorCounter()); +} + +static void cliVersion(char *cmdline) +{ + uartPrint("Afro32 CLI version 2.1 " __DATE__ " / " __TIME__); +} + +void cliProcess(void) +{ + if (!cliMode) { + cliMode = 1; + uartPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n"); + cliPrompt(); + } + + while (uartAvailable()) { + uint8_t c = uartRead(); + if (c == '\t' || c == '?') { + // do tab completion + const clicmd_t *cmd, *pstart = NULL, *pend = NULL; + int i = bufferIndex; + for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) { + if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0)) + continue; + if (!pstart) + pstart = cmd; + pend = cmd; + } + if (pstart) { /* Buffer matches one or more commands */ + for (; ; bufferIndex++) { + if (pstart->name[bufferIndex] != pend->name[bufferIndex]) + break; + if (!pstart->name[bufferIndex]) { + /* Unambiguous -- append a space */ + cliBuffer[bufferIndex++] = ' '; + break; + } + cliBuffer[bufferIndex] = pstart->name[bufferIndex]; + } + } + if (!bufferIndex || pstart != pend) { + /* Print list of ambiguous matches */ + uartPrint("\r\033[K"); + for (cmd = pstart; cmd <= pend; cmd++) { + uartPrint(cmd->name); + uartWrite('\t'); + } + cliPrompt(); + i = 0; /* Redraw prompt */ + } + for (; i < bufferIndex; i++) + uartWrite(cliBuffer[i]); + } else if (!bufferIndex && c == 4) { + cliExit(cliBuffer); + return; + } else if (c == 12) { + // clear screen + uartPrint("\033[2J\033[1;1H"); + cliPrompt(); + } else if (bufferIndex && (c == '\n' || c == '\r')) { + // enter pressed + clicmd_t *cmd = NULL; + clicmd_t target; + uartPrint("\r\n"); + cliBuffer[bufferIndex] = 0; // null terminate + + target.name = cliBuffer; + target.param = NULL; + + cmd = bsearch(&target, cmdTable, CMD_COUNT, sizeof cmdTable[0], cliCompare); + if (cmd) + cmd->func(cliBuffer + strlen(cmd->name) + 1); + else + uartPrint("ERR: Unknown command, try 'help'"); + + memset(cliBuffer, 0, sizeof(cliBuffer)); + bufferIndex = 0; + + // 'exit' will reset this flag, so we don't need to print prompt again + if (!cliMode) + return; + cliPrompt(); + } else if (c == 127) { + // backspace + if (bufferIndex) { + cliBuffer[--bufferIndex] = 0; + uartPrint("\010 \010"); + } + } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) { + if (!bufferIndex && c == 32) + continue; + cliBuffer[bufferIndex++] = c; + uartWrite(c); + } + } +} diff --git a/src/baseflight/src/config.c b/src/baseflight/src/config.c new file mode 100755 index 0000000000..fd25704fe5 --- /dev/null +++ b/src/baseflight/src/config.c @@ -0,0 +1,312 @@ +#include "board.h" +#include "mw.h" +#include + +#ifndef FLASH_PAGE_COUNT +#define FLASH_PAGE_COUNT 128 +#endif + +#define FLASH_PAGE_SIZE ((uint16_t)0x400) +#define FLASH_WRITE_ADDR (0x08000000 + (uint32_t)FLASH_PAGE_SIZE * (FLASH_PAGE_COUNT - 1)) // use the last KB for storage + +config_t cfg; +const char rcChannelLetters[] = "AERT1234"; + +static uint8_t EEPROM_CONF_VERSION = 34; +static uint32_t enabledSensors = 0; +static void resetConf(void); + +void parseRcChannels(const char *input) +{ + const char *c, *s; + + for (c = input; *c; c++) { + s = strchr(rcChannelLetters, *c); + if (s) + cfg.rcmap[s - rcChannelLetters] = c - input; + } +} + +static uint8_t validEEPROM(void) +{ + const config_t *temp = (const config_t *)FLASH_WRITE_ADDR; + const uint8_t *p; + uint8_t chk = 0; + + // check version number + if (EEPROM_CONF_VERSION != temp->version) + return 0; + + // check size and magic numbers + if (temp->size != sizeof(config_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF) + return 0; + + // verify integrity of temporary copy + for (p = (const uint8_t *)temp; p < ((const uint8_t *)temp + sizeof(config_t)); p++) + chk ^= *p; + + // checksum failed + if (chk != 0) + return 0; + + // looks good, let's roll! + return 1; +} + +void readEEPROM(void) +{ + uint8_t i; + + // Read flash + memcpy(&cfg, (char *)FLASH_WRITE_ADDR, sizeof(config_t)); + + for (i = 0; i < 6; i++) + lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500; + + for (i = 0; i < 11; i++) { + int16_t tmp = 10 * i - cfg.thrMid8; + uint8_t y = 1; + if (tmp > 0) + y = 100 - cfg.thrMid8; + if (tmp < 0) + y = cfg.thrMid8; + lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t) cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10; // [0;1000] + lookupThrottleRC[i] = cfg.minthrottle + (int32_t) (cfg.maxthrottle - cfg.minthrottle) * lookupThrottleRC[i] / 1000; // [0;1000] -> [MINTHROTTLE;MAXTHROTTLE] + } + + cfg.tri_yaw_middle = constrain(cfg.tri_yaw_middle, cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR +} + +void writeParams(uint8_t b) +{ + FLASH_Status status; + uint32_t i; + uint8_t chk = 0; + const uint8_t *p; + + cfg.version = EEPROM_CONF_VERSION; + cfg.size = sizeof(config_t); + cfg.magic_be = 0xBE; + cfg.magic_ef = 0xEF; + cfg.chk = 0; + // recalculate checksum before writing + for (p = (const uint8_t *)&cfg; p < ((const uint8_t *)&cfg + sizeof(config_t)); p++) + chk ^= *p; + cfg.chk = chk; + + // write it + FLASH_Unlock(); + FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR); + + if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE) { + for (i = 0; i < sizeof(config_t); i += 4) { + status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *) ((char *) &cfg + i)); + if (status != FLASH_COMPLETE) + break; // TODO: fail + } + } + FLASH_Lock(); + + readEEPROM(); + if (b) + blinkLED(15, 20, 1); +} + +void checkFirstTime(bool reset) +{ + // check the EEPROM integrity before resetting values + if (!validEEPROM() || reset) + resetConf(); +} + +// Default settings +static void resetConf(void) +{ + int i; + const int8_t default_align[3][3] = { /* GYRO */ { 0, 0, 0 }, /* ACC */ { 0, 0, 0 }, /* MAG */ { -2, -3, 1 } }; + + memset(&cfg, 0, sizeof(config_t)); + + cfg.version = EEPROM_CONF_VERSION; + cfg.mixerConfiguration = MULTITYPE_QUADX; + featureClearAll(); + featureSet(FEATURE_VBAT); + + // cfg.looptime = 0; + cfg.P8[ROLL] = 40; + cfg.I8[ROLL] = 30; + cfg.D8[ROLL] = 23; + cfg.P8[PITCH] = 40; + cfg.I8[PITCH] = 30; + cfg.D8[PITCH] = 23; + cfg.P8[YAW] = 85; + cfg.I8[YAW] = 45; + // cfg.D8[YAW] = 0; + cfg.P8[PIDALT] = 16; + cfg.I8[PIDALT] = 15; + cfg.D8[PIDALT] = 7; + cfg.P8[PIDPOS] = 11; // POSHOLD_P * 100; + // cfg.I8[PIDPOS] = 0; // POSHOLD_I * 100; + // cfg.D8[PIDPOS] = 0; + cfg.P8[PIDPOSR] = 20; // POSHOLD_RATE_P * 10; + cfg.I8[PIDPOSR] = 8; // POSHOLD_RATE_I * 100; + cfg.D8[PIDPOSR] = 45; // POSHOLD_RATE_D * 1000; + cfg.P8[PIDNAVR] = 14; // NAV_P * 10; + cfg.I8[PIDNAVR] = 20; // NAV_I * 100; + cfg.D8[PIDNAVR] = 80; // NAV_D * 1000; + cfg.P8[PIDLEVEL] = 70; + cfg.I8[PIDLEVEL] = 10; + cfg.D8[PIDLEVEL] = 20; + cfg.P8[PIDMAG] = 40; + // cfg.P8[PIDVEL] = 0; + // cfg.I8[PIDVEL] = 0; + // cfg.D8[PIDVEL] = 0; + cfg.rcRate8 = 90; + cfg.rcExpo8 = 65; + // cfg.rollPitchRate = 0; + // cfg.yawRate = 0; + // cfg.dynThrPID = 0; + cfg.thrMid8 = 50; + // cfg.thrExpo8 = 0; + // for (i = 0; i < CHECKBOXITEMS; i++) + // cfg.activate[i] = 0; + // cfg.angleTrim[0] = 0; + // cfg.angleTrim[1] = 0; + // cfg.accZero[0] = 0; + // cfg.accZero[1] = 0; + // cfg.accZero[2] = 0; + // cfg.mag_declination = 0; // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. + memcpy(&cfg.align, default_align, sizeof(cfg.align)); + cfg.acc_hardware = ACC_DEFAULT; // default/autodetect + cfg.acc_lpf_factor = 4; + cfg.acc_lpf_for_velocity = 10; + cfg.accz_deadband = 50; + cfg.gyro_cmpf_factor = 400; // default MWC + cfg.gyro_lpf = 42; + cfg.mpu6050_scale = 1; // fuck invensense + cfg.baro_tab_size = 21; + cfg.baro_noise_lpf = 0.6f; + cfg.baro_cf = 0.985f; + cfg.moron_threshold = 32; + cfg.gyro_smoothing_factor = 0x00141403; // default factors of 20, 20, 3 for R/P/Y + cfg.vbatscale = 110; + cfg.vbatmaxcellvoltage = 43; + cfg.vbatmincellvoltage = 33; + // cfg.power_adc_channel = 0; + + // Radio + parseRcChannels("AETR1234"); + // cfg.deadband = 0; + // cfg.yawdeadband = 0; + cfg.alt_hold_throttle_neutral = 20; + // cfg.spektrum_hires = 0; + cfg.midrc = 1500; + cfg.mincheck = 1100; + cfg.maxcheck = 1900; + // cfg.retarded_arm = 0; // disable arm/disarm on roll left/right + + // Failsafe Variables + cfg.failsafe_delay = 10; // 1sec + cfg.failsafe_off_delay = 200; // 20sec + cfg.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people. + + // Motor/ESC/Servo + cfg.minthrottle = 1150; + cfg.maxthrottle = 1850; + cfg.mincommand = 1000; + cfg.motor_pwm_rate = 400; + cfg.servo_pwm_rate = 50; + + // servos + cfg.yaw_direction = 1; + cfg.tri_yaw_middle = 1500; + cfg.tri_yaw_min = 1020; + cfg.tri_yaw_max = 2000; + + // flying wing + cfg.wing_left_min = 1020; + cfg.wing_left_mid = 1500; + cfg.wing_left_max = 2000; + cfg.wing_right_min = 1020; + cfg.wing_right_mid = 1500; + cfg.wing_right_max = 2000; + cfg.pitch_direction_l = 1; + cfg.pitch_direction_r = -1; + cfg.roll_direction_l = 1; + cfg.roll_direction_r = 1; + + // gimbal + cfg.gimbal_pitch_gain = 10; + cfg.gimbal_roll_gain = 10; + cfg.gimbal_flags = GIMBAL_NORMAL; + cfg.gimbal_pitch_min = 1020; + cfg.gimbal_pitch_max = 2000; + cfg.gimbal_pitch_mid = 1500; + cfg.gimbal_roll_min = 1020; + cfg.gimbal_roll_max = 2000; + cfg.gimbal_roll_mid = 1500; + + // gps/nav stuff + cfg.gps_type = GPS_NMEA; + cfg.gps_baudrate = 115200; + cfg.gps_wp_radius = 200; + cfg.gps_lpf = 20; + cfg.nav_slew_rate = 30; + cfg.nav_controls_heading = 1; + cfg.nav_speed_min = 100; + cfg.nav_speed_max = 300; + + // serial (USART1) baudrate + cfg.serial_baudrate = 115200; + + // custom mixer. clear by defaults. + for (i = 0; i < MAX_MOTORS; i++) + cfg.customMixer[i].throttle = 0.0f; + + writeParams(0); +} + +bool sensors(uint32_t mask) +{ + return enabledSensors & mask; +} + +void sensorsSet(uint32_t mask) +{ + enabledSensors |= mask; +} + +void sensorsClear(uint32_t mask) +{ + enabledSensors &= ~(mask); +} + +uint32_t sensorsMask(void) +{ + return enabledSensors; +} + +bool feature(uint32_t mask) +{ + return cfg.enabledFeatures & mask; +} + +void featureSet(uint32_t mask) +{ + cfg.enabledFeatures |= mask; +} + +void featureClear(uint32_t mask) +{ + cfg.enabledFeatures &= ~(mask); +} + +void featureClearAll() +{ + cfg.enabledFeatures = 0; +} + +uint32_t featureMask(void) +{ + return cfg.enabledFeatures; +} diff --git a/src/baseflight/src/drv_adc.c b/src/baseflight/src/drv_adc.c new file mode 100755 index 0000000000..022cc74619 --- /dev/null +++ b/src/baseflight/src/drv_adc.c @@ -0,0 +1,60 @@ +#include "board.h" + +#define ADC_BATTERY 0 +#define ADC_CURRENT 1 + +// static volatile uint16_t adc1Ch4Value = 0; +static volatile uint16_t adcValues[2]; + +void adcInit(drv_adc_config_t *init) +{ + ADC_InitTypeDef ADC_InitStructure; + DMA_InitTypeDef DMA_InitStructure; + bool multiChannel = init->powerAdcChannel > 0; + + // ADC assumes all the GPIO was already placed in 'AIN' mode + DMA_DeInit(DMA1_Channel1); + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR; + DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)adcValues; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + DMA_InitStructure.DMA_BufferSize = multiChannel ? 2 : 1; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_MemoryInc = multiChannel ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; + DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; + DMA_InitStructure.DMA_Priority = DMA_Priority_High; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; + DMA_Init(DMA1_Channel1, &DMA_InitStructure); + /* Enable DMA1 channel1 */ + DMA_Cmd(DMA1_Channel1, ENABLE); + + ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; + ADC_InitStructure.ADC_ScanConvMode = multiChannel ? ENABLE : DISABLE; + ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; + ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; + ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; + ADC_InitStructure.ADC_NbrOfChannel = multiChannel ? 2 : 1; + ADC_Init(ADC1, &ADC_InitStructure); + + ADC_RegularChannelConfig(ADC1, ADC_Channel_4, 1, ADC_SampleTime_28Cycles5); + if (multiChannel) + ADC_RegularChannelConfig(ADC1, init->powerAdcChannel, 2, ADC_SampleTime_28Cycles5); + ADC_DMACmd(ADC1, ENABLE); + + ADC_Cmd(ADC1, ENABLE); + + // Calibrate ADC + ADC_ResetCalibration(ADC1); + while(ADC_GetResetCalibrationStatus(ADC1)); + ADC_StartCalibration(ADC1); + while(ADC_GetCalibrationStatus(ADC1)); + + // Fire off ADC + ADC_SoftwareStartConvCmd(ADC1, ENABLE); +} + +uint16_t adcGetChannel(uint8_t channel) +{ + return adcValues[channel]; +} diff --git a/src/baseflight/src/drv_adc.h b/src/baseflight/src/drv_adc.h new file mode 100755 index 0000000000..e33d6923f7 --- /dev/null +++ b/src/baseflight/src/drv_adc.h @@ -0,0 +1,15 @@ +#pragma once + +#define ADC_BATTERY 0 +#define ADC_CURRENT 1 + +typedef struct drv_adc_config_t { + uint8_t powerAdcChannel; // which channel used for current monitor, allowed PA1, PB1 (ADC_Channel_1, ADC_Channel_9) +} drv_adc_config_t; + + +void adcInit(drv_adc_config_t *init); +uint16_t adcGetChannel(uint8_t channel); +#ifdef FY90Q +void adcSensorInit(sensor_t *acc, sensor_t *gyro); +#endif diff --git a/src/baseflight/src/drv_adc_fy90q.c b/src/baseflight/src/drv_adc_fy90q.c new file mode 100644 index 0000000000..a57b754221 --- /dev/null +++ b/src/baseflight/src/drv_adc_fy90q.c @@ -0,0 +1,144 @@ +#ifdef FY90Q +#include "board.h" + +#define ADC_CHANNELS 9 + +volatile uint16_t adcData[ADC_CHANNELS] = { 0, }; +extern uint16_t acc_1G; + +static void adcAccRead(int16_t *accelData); +static void adcAccAlign(int16_t *accelData); +static void adcGyroRead(int16_t *gyroData); +static void adcGyroAlign(int16_t *gyroData); +static void adcDummyInit(void); + +void adcSensorInit(sensor_t *acc, sensor_t *gyro) +{ + acc->init = adcDummyInit; + acc->read = adcAccRead; + acc->align = adcAccAlign; + + gyro->init = adcDummyInit; + gyro->read = adcGyroRead; + gyro->align = adcGyroAlign; + + acc_1G = 376; +} + +void adcCalibrateADC(ADC_TypeDef *ADCx, int n) +{ + while (n > 0) { + delay(5); + // Enable ADC reset calibration register + ADC_ResetCalibration(ADCx); + // Check the end of ADC reset calibration register + while(ADC_GetResetCalibrationStatus(ADCx)); + // Start ADC calibration + ADC_StartCalibration(ADCx); + // Check the end of ADC calibration + while(ADC_GetCalibrationStatus(ADCx)); + n--; + } +} + +void adcInit(void) +{ + ADC_InitTypeDef ADC_InitStructure; + DMA_InitTypeDef DMA_InitStructure; + + // ADC assumes all the GPIO was already placed in 'AIN' mode + DMA_DeInit(DMA1_Channel1); + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR; + DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)&adcData; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + DMA_InitStructure.DMA_BufferSize = ADC_CHANNELS; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord; + DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; + DMA_InitStructure.DMA_Priority = DMA_Priority_High; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; + DMA_Init(DMA1_Channel1, &DMA_InitStructure); + /* Enable DMA1 channel1 */ + DMA_Cmd(DMA1_Channel1, ENABLE); + + ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; + ADC_InitStructure.ADC_ScanConvMode = ENABLE; + ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; + ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; + ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; + ADC_InitStructure.ADC_NbrOfChannel = ADC_CHANNELS; + ADC_Init(ADC1, &ADC_InitStructure); + + ADC_RegularChannelConfig(ADC1, ADC_Channel_10, 1, ADC_SampleTime_28Cycles5); // GY_X + ADC_RegularChannelConfig(ADC1, ADC_Channel_11, 2, ADC_SampleTime_28Cycles5); // GY_Y + ADC_RegularChannelConfig(ADC1, ADC_Channel_12, 3, ADC_SampleTime_28Cycles5); // GY_Z + + ADC_RegularChannelConfig(ADC1, ADC_Channel_13, 4, ADC_SampleTime_28Cycles5); // ACC_X + ADC_RegularChannelConfig(ADC1, ADC_Channel_14, 5, ADC_SampleTime_28Cycles5); // ACC_Y + ADC_RegularChannelConfig(ADC1, ADC_Channel_15, 6, ADC_SampleTime_28Cycles5); // ACC_Z + + ADC_RegularChannelConfig(ADC1, ADC_Channel_5, 7, ADC_SampleTime_28Cycles5); // POT_ELE + ADC_RegularChannelConfig(ADC1, ADC_Channel_6, 8, ADC_SampleTime_28Cycles5); // POT_AIL + ADC_RegularChannelConfig(ADC1, ADC_Channel_7, 9, ADC_SampleTime_28Cycles5); // POT_RUD + + ADC_DMACmd(ADC1, ENABLE); + + ADC_Cmd(ADC1, ENABLE); + + // Calibrate ADC + adcCalibrateADC(ADC1, 2); + + // Fire off ADC + ADC_SoftwareStartConvCmd(ADC1, ENABLE); +} + +static void adcAccRead(int16_t *accelData) +{ + // ADXL335 + // 300mV/g + // Vcc 3.0V + accelData[0] = adcData[3]; + accelData[1] = adcData[4]; + accelData[2] = adcData[5]; +} + +static void adcAccAlign(int16_t *accelData) +{ + // align OK +} + +static void adcGyroRead(int16_t *gyroData) +{ + // Vcc: 3.0V + // Pitch/Roll: LPR550AL, 2000dps mode. + // 0.5mV/dps + // Zero-rate: 1.23V + // Yaw: LPY550AL, 2000dps mode. + // 0.5mV/dps + // Zero-rate: 1.23V + + // Need to match with: 14.375lsb per dps + // 12-bit ADC + + gyroData[0] = adcData[0] * 2; + gyroData[1] = adcData[1] * 2; + gyroData[2] = adcData[2] * 2; +} + +static void adcGyroAlign(int16_t *gyroData) +{ + // align OK +} + +static void adcDummyInit(void) +{ + // nothing to init here +} + +uint16_t adcGetBattery(void) +{ + return 0; +} +#endif diff --git a/src/baseflight/src/drv_adxl345.c b/src/baseflight/src/drv_adxl345.c new file mode 100755 index 0000000000..7d6245d047 --- /dev/null +++ b/src/baseflight/src/drv_adxl345.c @@ -0,0 +1,110 @@ +#include "board.h" + +// ADXL345, Alternative address mode 0x53 +#define ADXL345_ADDRESS 0x53 + +// Registers +#define ADXL345_BW_RATE 0x2C +#define ADXL345_POWER_CTL 0x2D +#define ADXL345_INT_ENABLE 0x2E +#define ADXL345_DATA_FORMAT 0x31 +#define ADXL345_DATA_OUT 0x32 +#define ADXL345_FIFO_CTL 0x38 + +// BW_RATE values +#define ADXL345_RATE_50 0x09 +#define ADXL345_RATE_100 0x0A +#define ADXL345_RATE_200 0x0B +#define ADXL345_RATE_400 0x0C +#define ADXL345_RATE_800 0x0D +#define ADXL345_RATE_1600 0x0E +#define ADXL345_RATE_3200 0x0F + +// various register values +#define ADXL345_POWER_MEAS 0x08 +#define ADXL345_FULL_RANGE 0x08 +#define ADXL345_RANGE_2G 0x00 +#define ADXL345_RANGE_4G 0x01 +#define ADXL345_RANGE_8G 0x02 +#define ADXL345_RANGE_16G 0x03 +#define ADXL345_FIFO_STREAM 0x80 + +extern uint16_t acc_1G; + +static void adxl345Init(void); +static void adxl345Read(int16_t *accelData); +static void adxl345Align(int16_t *accelData); + +static bool useFifo = false; + +bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc) +{ + bool ack = false; + uint8_t sig = 0; + + ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig); + if (!ack || sig != 0xE5) + return false; + + // use ADXL345's fifo to filter data or not + useFifo = init->useFifo; + + acc->init = adxl345Init; + acc->read = adxl345Read; + acc->align = adxl345Align; + return true; +} + +static void adxl345Init(void) +{ + if (useFifo) { + uint8_t fifoDepth = 16; + i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS); + i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G); + i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400); + i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM); + } else { + i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS); + i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G); + i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100); + } + acc_1G = 265; // 3.3V operation +} + +uint8_t acc_samples = 0; + +static void adxl345Read(int16_t *accelData) +{ + uint8_t buf[8]; + + if (useFifo) { + int32_t x = 0; + int32_t y = 0; + int32_t z = 0; + uint8_t i = 0; + uint8_t samples_remaining; + + do { + i++; + i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf); + x += (int16_t)(buf[0] + (buf[1] << 8)); + y += (int16_t)(buf[2] + (buf[3] << 8)); + z += (int16_t)(buf[4] + (buf[5] << 8)); + samples_remaining = buf[7] & 0x7F; + } while ((i < 32) && (samples_remaining > 0)); + accelData[0] = x / i; + accelData[1] = y / i; + accelData[2] = z / i; + acc_samples = i; + } else { + i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf); + accelData[0] = buf[0] + (buf[1] << 8); + accelData[1] = buf[2] + (buf[3] << 8); + accelData[2] = buf[4] + (buf[5] << 8); + } +} + +static void adxl345Align(int16_t *accData) +{ + // official direction is RPY, nothing to change here. +} diff --git a/src/baseflight/src/drv_adxl345.h b/src/baseflight/src/drv_adxl345.h new file mode 100755 index 0000000000..564ccc4df7 --- /dev/null +++ b/src/baseflight/src/drv_adxl345.h @@ -0,0 +1,8 @@ +#pragma once + +typedef struct drv_adxl345_config_t { + bool useFifo; + uint16_t dataRate; +} drv_adxl345_config_t; + +bool adxl345Detect(drv_adxl345_config_t *init, sensor_t *acc); diff --git a/src/baseflight/src/drv_bmp085.c b/src/baseflight/src/drv_bmp085.c new file mode 100755 index 0000000000..31571b2c57 --- /dev/null +++ b/src/baseflight/src/drv_bmp085.c @@ -0,0 +1,296 @@ +#include "board.h" + +// BMP085, Standard address 0x77 +static bool convDone = false; +static uint16_t convOverrun = 0; + +#define BARO_OFF digitalLo(BARO_GPIO, BARO_PIN); +#define BARO_ON digitalHi(BARO_GPIO, BARO_PIN); + +// EXTI14 for BMP085 End of Conversion Interrupt +void EXTI15_10_IRQHandler(void) +{ + if (EXTI_GetITStatus(EXTI_Line14) == SET) { + EXTI_ClearITPendingBit(EXTI_Line14); + convDone = true; + } +} + +typedef struct { + int16_t ac1; + int16_t ac2; + int16_t ac3; + uint16_t ac4; + uint16_t ac5; + uint16_t ac6; + int16_t b1; + int16_t b2; + int16_t mb; + int16_t mc; + int16_t md; +} bmp085_smd500_calibration_param_t; + +typedef struct { + bmp085_smd500_calibration_param_t cal_param; + uint8_t mode; + uint8_t chip_id, ml_version, al_version; + uint8_t dev_addr; + int32_t param_b5; + int16_t oversampling_setting; +} bmp085_t; + +#define BMP085_I2C_ADDR 0x77 +#define BMP085_CHIP_ID 0x55 +#define BOSCH_PRESSURE_BMP085 85 +#define BMP085_CHIP_ID_REG 0xD0 +#define BMP085_VERSION_REG 0xD1 +#define E_SENSOR_NOT_DETECTED (char) 0 +#define BMP085_PROM_START__ADDR 0xaa +#define BMP085_PROM_DATA__LEN 22 +#define BMP085_T_MEASURE 0x2E // temperature measurent +#define BMP085_P_MEASURE 0x34 // pressure measurement +#define BMP085_CTRL_MEAS_REG 0xF4 +#define BMP085_ADC_OUT_MSB_REG 0xF6 +#define BMP085_ADC_OUT_LSB_REG 0xF7 +#define BMP085_CHIP_ID__POS 0 +#define BMP085_CHIP_ID__MSK 0xFF +#define BMP085_CHIP_ID__LEN 8 +#define BMP085_CHIP_ID__REG BMP085_CHIP_ID_REG + +#define BMP085_ML_VERSION__POS 0 +#define BMP085_ML_VERSION__LEN 4 +#define BMP085_ML_VERSION__MSK 0x0F +#define BMP085_ML_VERSION__REG BMP085_VERSION_REG + +#define BMP085_AL_VERSION__POS 4 +#define BMP085_AL_VERSION__LEN 4 +#define BMP085_AL_VERSION__MSK 0xF0 +#define BMP085_AL_VERSION__REG BMP085_VERSION_REG + +#define BMP085_GET_BITSLICE(regvar, bitname) (regvar & bitname##__MSK) >> bitname##__POS +#define BMP085_SET_BITSLICE(regvar, bitname, val) (regvar & ~bitname##__MSK) | ((val<ut_delay = 4600; + baro->up_delay = 26000; + baro->repeat_delay = 5000; + baro->start_ut = bmp085_start_ut; + baro->get_ut = bmp085_get_ut; + baro->start_up = bmp085_start_up; + baro->get_up = bmp085_get_up; + baro->calculate = bmp085_calculate; + return true; + } + BARO_OFF; + return false; +} + +// #define BMP_TEMP_OSS 4 +static int16_t bmp085_get_temperature(uint32_t ut) +{ + int16_t temperature; + int32_t x1, x2; +#ifdef BMP_TEMP_OSS + static uint32_t temp; +#endif + + x1 = (((int32_t) ut - (int32_t) bmp085.cal_param.ac6) * (int32_t) bmp085.cal_param.ac5) >> 15; + x2 = ((int32_t) bmp085.cal_param.mc << 11) / (x1 + bmp085.cal_param.md); + bmp085.param_b5 = x1 + x2; + temperature = ((bmp085.param_b5 + 8) >> 4); // temperature in 0.1°C + +#ifdef BMP_TEMP_OSS + temp *= (1 << BMP_TEMP_OSS) - 1; // multiply the temperature variable by 3 - we have tau == 1/4 + temp += ((uint32_t)temperature) << 8; // add on the buffer + temp >>= BMP_TEMP_OSS; // divide by 4 + return (int16_t)temp; +#else + return temperature; +#endif +} + +static int32_t bmp085_get_pressure(uint32_t up) +{ + int32_t pressure, x1, x2, x3, b3, b6; + uint32_t b4, b7; + + b6 = bmp085.param_b5 - 4000; + // *****calculate B3************ + x1 = (b6 * b6) >> 12; + x1 *= bmp085.cal_param.b2; + x1 >>= 11; + + x2 = (bmp085.cal_param.ac2 * b6); + x2 >>= 11; + + x3 = x1 + x2; + + b3 = (((((int32_t)bmp085.cal_param.ac1) * 4 + x3) << bmp085.oversampling_setting) + 2) >> 2; + + // *****calculate B4************ + x1 = (bmp085.cal_param.ac3 * b6) >> 13; + x2 = (bmp085.cal_param.b1 * ((b6 * b6) >> 12) ) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + b4 = (bmp085.cal_param.ac4 * (uint32_t) (x3 + 32768)) >> 15; + + b7 = ((uint32_t)(up - b3) * (50000 >> bmp085.oversampling_setting)); + if (b7 < 0x80000000) { + pressure = (b7 << 1) / b4; + } else { + pressure = (b7 / b4) << 1; + } + + x1 = pressure >> 8; + x1 *= x1; + x1 = (x1 * SMD500_PARAM_MG) >> 16; + x2 = (pressure * SMD500_PARAM_MH) >> 16; + pressure += (x1 + x2 + SMD500_PARAM_MI) >> 4; // pressure in Pa + + return pressure; +} + +static void bmp085_start_ut(void) +{ + convDone = false; + i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE); +} + +static void bmp085_get_ut(void) +{ + uint8_t data[2]; + uint16_t timeout = 10000; + + // wait in case of cockup + if (!convDone) + convOverrun++; +#if 0 + while (!convDone && timeout-- > 0) { + __NOP(); + } +#endif + i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data); + bmp085_ut = (data[0] << 8) | data[1]; +} + +static void bmp085_start_up(void) +{ + uint8_t ctrl_reg_data; + + ctrl_reg_data = BMP085_P_MEASURE + (bmp085.oversampling_setting << 6); + convDone = false; + i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data); +} + +/** read out up for pressure conversion + depending on the oversampling ratio setting up can be 16 to 19 bit + \return up parameter that represents the uncompensated pressure value +*/ +static void bmp085_get_up(void) +{ + uint8_t data[3]; + uint16_t timeout = 10000; + + // wait in case of cockup + if (!convDone) + convOverrun++; +#if 0 + while (!convDone && timeout-- > 0) { + __NOP(); + } +#endif + i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data); + bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - bmp085.oversampling_setting); +} + +static int32_t bmp085_calculate(void) +{ + bmp085_get_temperature(bmp085_ut); + return bmp085_get_pressure(bmp085_up); +} + +static void bmp085_get_cal_param(void) +{ + uint8_t data[22]; + i2cRead(BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data); + + /*parameters AC1-AC6*/ + bmp085.cal_param.ac1 = (data[0] << 8) | data[1]; + bmp085.cal_param.ac2 = (data[2] << 8) | data[3]; + bmp085.cal_param.ac3 = (data[4] << 8) | data[5]; + bmp085.cal_param.ac4 = (data[6] << 8) | data[7]; + bmp085.cal_param.ac5 = (data[8] << 8) | data[9]; + bmp085.cal_param.ac6 = (data[10] << 8) | data[11]; + + /*parameters B1,B2*/ + bmp085.cal_param.b1 = (data[12] << 8) | data[13]; + bmp085.cal_param.b2 = (data[14] << 8) | data[15]; + + /*parameters MB,MC,MD*/ + bmp085.cal_param.mb = (data[16] << 8) | data[17]; + bmp085.cal_param.mc = (data[18] << 8) | data[19]; + bmp085.cal_param.md = (data[20] << 8) | data[21]; +} diff --git a/src/baseflight/src/drv_bmp085.h b/src/baseflight/src/drv_bmp085.h new file mode 100755 index 0000000000..3c063fae26 --- /dev/null +++ b/src/baseflight/src/drv_bmp085.h @@ -0,0 +1,3 @@ +#pragma once + +bool bmp085Detect(baro_t *baro); diff --git a/src/baseflight/src/drv_hcsr04.c b/src/baseflight/src/drv_hcsr04.c new file mode 100644 index 0000000000..83c2fe8277 --- /dev/null +++ b/src/baseflight/src/drv_hcsr04.c @@ -0,0 +1,132 @@ +#include "board.h" +#include "mw.h" + +#ifdef SONAR + +/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits. + * When trigged it sends out a series of 40KHz ultrasonic pulses and receives + * echo froman object. The distance between the unit and the object is calculated + * by measuring the traveling time of sound and output it as the width of a TTL pulse. + * + * *** Warning: HC-SR04 operates at +5V *** + * + */ + +static uint16_t trigger_pin; +static uint16_t echo_pin; +static uint32_t exti_line; +static uint8_t exti_pin_source; +static IRQn_Type exti_irqn; + +static uint32_t last_measurement; +static volatile int16_t* distance_ptr; + +void ECHO_EXTI_IRQHandler(void) +{ + static uint32_t timing_start; + uint32_t timing_stop; + if(GPIO_ReadInputDataBit(GPIOB, echo_pin) != 0) + timing_start = micros(); + else + { + timing_stop = micros(); + if(timing_stop > timing_start) + { + // The speed of sound is 340 m/s or approx. 29 microseconds per centimeter. + // The ping travels out and back, so to find the distance of the + // object we take half of the distance traveled. + // + // 340 m/s = 0.034 cm/microsecond = 29.41176471 *2 = 58.82352941 rounded to 59 + int32_t pulse_duration = timing_stop - timing_start; + *distance_ptr = pulse_duration / 59 ; + } + } + + EXTI_ClearITPendingBit(exti_line); +} + +void EXTI1_IRQHandler(void) +{ + ECHO_EXTI_IRQHandler(); +} + +void EXTI9_5_IRQHandler(void) +{ + ECHO_EXTI_IRQHandler(); +} + +void hcsr04_init(sonar_config_t config) +{ + GPIO_InitTypeDef GPIO_InitStructure; + EXTI_InitTypeDef EXTIInit; + + //enable AFIO for EXTI support - already done is drv_system.c + //RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph, ENABLE); + + switch(config) + { + case sonar_pwm56: + trigger_pin = GPIO_Pin_8; // PWM5 (PB8) - 5v tolerant + echo_pin = GPIO_Pin_9; // PWM6 (PB9) - 5v tolerant + exti_line = EXTI_Line9; + exti_pin_source = GPIO_PinSource9; + exti_irqn = EXTI9_5_IRQn; + break; + case sonar_rc78: + trigger_pin = GPIO_Pin_0; // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) + echo_pin = GPIO_Pin_1; // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) + exti_line = EXTI_Line1; + exti_pin_source = GPIO_PinSource1; + exti_irqn = EXTI1_IRQn; + break; + } + + // tp - trigger pin + GPIO_InitStructure.GPIO_Pin = trigger_pin; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + // ep - echo pin + GPIO_InitStructure.GPIO_Pin = echo_pin; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + // setup external interrupt on echo pin + GPIO_EXTILineConfig(GPIO_PortSourceGPIOB, exti_pin_source); + + EXTI_ClearITPendingBit(exti_line); + + EXTIInit.EXTI_Line = exti_line; + EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt; + EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling; + EXTIInit.EXTI_LineCmd = ENABLE; + EXTI_Init(&EXTIInit); + + NVIC_EnableIRQ(exti_irqn); + + last_measurement = millis() - 60; // force 1st measurement in hcsr04_get_distance() +} + +// distance calculation is done asynchronously, using interrupt +void hcsr04_get_distance(volatile int16_t* distance) +{ + uint32_t current_time = millis(); + + if( current_time < (last_measurement + 60) ) + { + // the repeat interval of trig signal should be greater than 60ms + // to avoid interference between connective measurements. + return; + } + + last_measurement = current_time; + distance_ptr = distance; + + GPIO_SetBits(GPIOB, trigger_pin); + // The width of trig signal must be greater than 10us + delayMicroseconds(11); + GPIO_ResetBits(GPIOB, trigger_pin); +} + +#endif diff --git a/src/baseflight/src/drv_hcsr04.h b/src/baseflight/src/drv_hcsr04.h new file mode 100644 index 0000000000..2986f976b1 --- /dev/null +++ b/src/baseflight/src/drv_hcsr04.h @@ -0,0 +1,9 @@ +#pragma once + +typedef enum { + sonar_pwm56, + sonar_rc78, +} sonar_config_t; + +void hcsr04_init(sonar_config_t config); +void hcsr04_get_distance(volatile int16_t* distance); diff --git a/src/baseflight/src/drv_hmc5883l.c b/src/baseflight/src/drv_hmc5883l.c new file mode 100755 index 0000000000..31bfd8a124 --- /dev/null +++ b/src/baseflight/src/drv_hmc5883l.c @@ -0,0 +1,87 @@ +#include "board.h" + +// HMC5883L, default address 0x1E +// PB12 connected to MAG_DRDY on rev4 hardware + +#define MAG_ADDRESS 0x1E +#define MAG_DATA_REGISTER 0x03 +#define ConfigRegA 0x00 +#define ConfigRegB 0x01 +#define magGain 0x20 +#define PositiveBiasConfig 0x11 +#define NegativeBiasConfig 0x12 +#define NormalOperation 0x10 +#define ModeRegister 0x02 +#define ContinuousConversion 0x00 +#define SingleConversion 0x01 + +// ConfigRegA valid sample averaging for 5883L +#define SampleAveraging_1 0x00 +#define SampleAveraging_2 0x01 +#define SampleAveraging_4 0x02 +#define SampleAveraging_8 0x03 + +// ConfigRegA valid data output rates for 5883L +#define DataOutputRate_0_75HZ 0x00 +#define DataOutputRate_1_5HZ 0x01 +#define DataOutputRate_3HZ 0x02 +#define DataOutputRate_7_5HZ 0x03 +#define DataOutputRate_15HZ 0x04 +#define DataOutputRate_30HZ 0x05 +#define DataOutputRate_75HZ 0x06 + +bool hmc5883lDetect(void) +{ + bool ack = false; + uint8_t sig = 0; + + ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig); + if (!ack || sig != 'H') + return false; + + return true; +} + +void hmc5883lInit(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + // PB12 - MAG_DRDY output on rev4 hardware + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + delay(100); + i2cWrite(MAG_ADDRESS, ConfigRegA, SampleAveraging_8 << 5 | DataOutputRate_75HZ << 2 | NormalOperation); + delay(50); +} + +void hmc5883lCal(uint8_t calibration_gain) +{ + // force positiveBias (compass should return 715 for all channels) + i2cWrite(MAG_ADDRESS, ConfigRegA, SampleAveraging_8 << 5 | DataOutputRate_75HZ << 2 | PositiveBiasConfig); + delay(50); + // set gains for calibration + i2cWrite(MAG_ADDRESS, ConfigRegB, calibration_gain); + i2cWrite(MAG_ADDRESS, ModeRegister, SingleConversion); +} + +void hmc5883lFinishCal(void) +{ + // leave test mode + i2cWrite(MAG_ADDRESS, ConfigRegA, SampleAveraging_8 << 5 | DataOutputRate_75HZ << 2 | NormalOperation); + i2cWrite(MAG_ADDRESS, ConfigRegB, magGain); + i2cWrite(MAG_ADDRESS, ModeRegister, ContinuousConversion); +} + +void hmc5883lRead(int16_t *magData) +{ + uint8_t buf[6]; + + i2cRead(MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); + + magData[0] = buf[0] << 8 | buf[1]; + magData[1] = buf[2] << 8 | buf[3]; + magData[2] = buf[4] << 8 | buf[5]; +} diff --git a/src/baseflight/src/drv_hmc5883l.h b/src/baseflight/src/drv_hmc5883l.h new file mode 100755 index 0000000000..ac87f1daef --- /dev/null +++ b/src/baseflight/src/drv_hmc5883l.h @@ -0,0 +1,7 @@ +#pragma once + +bool hmc5883lDetect(void); +void hmc5883lInit(void); +void hmc5883lCal(uint8_t calibration_gain); +void hmc5883lFinishCal(void); +void hmc5883lRead(int16_t *magData); diff --git a/src/baseflight/src/drv_i2c.c b/src/baseflight/src/drv_i2c.c new file mode 100755 index 0000000000..270d971ea4 --- /dev/null +++ b/src/baseflight/src/drv_i2c.c @@ -0,0 +1,356 @@ +#include "board.h" + +#ifndef SOFT_I2C + +// I2C2 +// SCL PB10 +// SDA PB11 + +static I2C_TypeDef *I2Cx; +static void i2c_er_handler(void); +static void i2c_ev_handler(void); +static void i2cUnstick(void); + +void I2C1_ER_IRQHandler(void) +{ + i2c_er_handler(); +} + +void I2C1_EV_IRQHandler(void) +{ + i2c_ev_handler(); +} + +void I2C2_ER_IRQHandler(void) +{ + i2c_er_handler(); +} + +void I2C2_EV_IRQHandler(void) +{ + i2c_ev_handler(); +} + + +#define I2C_DEFAULT_TIMEOUT 30000 +static volatile uint16_t i2cErrorCount = 0; + +static volatile bool error = false; +static volatile bool busy; + +static volatile uint8_t addr; +static volatile uint8_t reg; +static volatile uint8_t bytes; +static volatile uint8_t writing; +static volatile uint8_t reading; +static volatile uint8_t* write_p; +static volatile uint8_t* read_p; + +static void i2c_er_handler(void) +{ + volatile uint32_t SR1Register, SR2Register; + /* Read the I2C1 status register */ + SR1Register = I2Cx->SR1; + if (SR1Register & 0x0F00) { //an error + error = true; + // I2C1error.error = ((SR1Register & 0x0F00) >> 8); //save error + // I2C1error.job = job; //the task + } + /* If AF, BERR or ARLO, abandon the current job and commence new if there are jobs */ + if (SR1Register & 0x0700) { + SR2Register = I2Cx->SR2; //read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK) + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully) + if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { //if we dont have an ARLO error, ensure sending of a stop + if (I2Cx->CR1 & 0x0100) { //We are currently trying to send a start, this is very bad as start,stop will hang the peripheral + while (I2Cx->CR1 & 0x0100); //wait for any start to finish sending + I2C_GenerateSTOP(I2Cx, ENABLE); //send stop to finalise bus transaction + while (I2Cx->CR1 & 0x0200); //wait for stop to finish sending + i2cInit(I2Cx); //reset and configure the hardware + } else { + I2C_GenerateSTOP(I2Cx, ENABLE); //stop to free up the bus + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Disable EVT and ERR interrupts while bus inactive + } + } + } + I2Cx->SR1 &= ~0x0F00; //reset all the error bits to clear the interrupt + busy = 0; +} + +bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) +{ + uint8_t i; + uint8_t my_data[16]; + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 1; + reading = 0; + write_p = my_data; + read_p = my_data; + bytes = len_; + busy = 1; + error = false; + + // too long + if (len_ > 16) + return false; + + for (i = 0; i < len_; i++) + my_data[i] = data[i]; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { //if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200) { ; } //wait for any stop to finish sending + I2C_GenerateSTART(I2Cx, ENABLE); //send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); //allow the interrupts to fire off again + } + + while (busy && --timeout > 0); + if (timeout == 0) { + i2cErrorCount++; + // reinit peripheral + clock out garbage + i2cInit(I2Cx); + return false; + } + + return !error; +} + +bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +{ + return i2cWriteBuffer(addr_, reg_, 1, &data); +} + +bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) +{ + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + + addr = addr_ << 1; + reg = reg_; + writing = 0; + reading = 1; + read_p = buf; + write_p = buf; + bytes = len; + busy = 1; + error = false; + + if (!(I2Cx->CR2 & I2C_IT_EVT)) { //if we are restarting the driver + if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start + while (I2Cx->CR1 & 0x0200) { ; } //wait for any stop to finish sending + I2C_GenerateSTART(I2Cx, ENABLE); //send the start for the new job + } + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); //allow the interrupts to fire off again + } + + while (busy && --timeout > 0); + if (timeout == 0) { + i2cErrorCount++; + // reinit peripheral + clock out garbage + i2cInit(I2Cx); + return false; + } + + return !error; +} + +void i2c_ev_handler(void) +{ + static uint8_t subaddress_sent, final_stop; //flag to indicate if subaddess sent, flag to indicate final bus condition + static int8_t index; //index is signed -1==send the subaddress + uint8_t SReg_1 = I2Cx->SR1; //read the status register here + + if (SReg_1 & 0x0001) { //we just sent a start - EV5 in ref manual + I2Cx->CR1 &= ~0x0800; //reset the POS bit so ACK/NACK applied to the current byte + I2C_AcknowledgeConfig(I2Cx, ENABLE); //make sure ACK is on + index = 0; //reset the index + if (reading && (subaddress_sent || 0xFF == reg)) { //we have sent the subaddr + subaddress_sent = 1; //make sure this is set in case of no subaddress, so following code runs correctly + if (bytes == 2) + I2Cx->CR1 |= 0x0800; //set the POS bit so NACK applied to the final byte in the two byte read + I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Receiver); //send the address and set hardware mode + } else { //direction is Tx, or we havent sent the sub and rep start + I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Transmitter); //send the address and set hardware mode + if (reg != 0xFF) //0xFF as subaddress means it will be ignored, in Tx or Rx mode + index = -1; //send a subaddress + } + } else if (SReg_1 & 0x0002) { //we just sent the address - EV6 in ref manual + //Read SR1,2 to clear ADDR + volatile uint8_t a; + __DMB(); // memory fence to control hardware + if (bytes == 1 && reading && subaddress_sent) { //we are receiving 1 byte - EV6_3 + I2C_AcknowledgeConfig(I2Cx, DISABLE); //turn off ACK + __DMB(); + a = I2Cx->SR2; //clear ADDR after ACK is turned off + I2C_GenerateSTOP(I2Cx, ENABLE); //program the stop + final_stop = 1; + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); //allow us to have an EV7 + } else { //EV6 and EV6_1 + a = I2Cx->SR2; //clear the ADDR here + __DMB(); + if (bytes == 2 && reading && subaddress_sent) { //rx 2 bytes - EV6_1 + I2C_AcknowledgeConfig(I2Cx, DISABLE); //turn off ACK + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to fill + } else if (bytes == 3 && reading && subaddress_sent) //rx 3 bytes + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //make sure RXNE disabled so we get a BTF in two bytes time + else //receiving greater than three bytes, sending subaddress, or transmitting + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); + } + } else if (SReg_1 & 0x004) { //Byte transfer finished - EV7_2, EV7_3 or EV8_2 + final_stop = 1; + if (reading && subaddress_sent) { //EV7_2, EV7_3 + if (bytes > 2) { //EV7_2 + I2C_AcknowledgeConfig(I2Cx, DISABLE); //turn off ACK + read_p[index++] = I2C_ReceiveData(I2Cx); //read data N-2 + I2C_GenerateSTOP(I2Cx, ENABLE); //program the Stop + final_stop = 1; //reuired to fix hardware + read_p[index++] = I2C_ReceiveData(I2Cx); //read data N-1 + I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); //enable TXE to allow the final EV7 + } else { //EV7_3 + if (final_stop) + I2C_GenerateSTOP(I2Cx, ENABLE); //program the Stop + else + I2C_GenerateSTART(I2Cx, ENABLE); //program a rep start + read_p[index++] = I2C_ReceiveData(I2Cx); //read data N-1 + read_p[index++] = I2C_ReceiveData(I2Cx); //read data N + index++; //to show job completed + } + } else { //EV8_2, which may be due to a subaddress sent or a write completion + if (subaddress_sent || (writing)) { + if (final_stop) + I2C_GenerateSTOP(I2Cx, ENABLE); //program the Stop + else + I2C_GenerateSTART(I2Cx, ENABLE); //program a rep start + index++; //to show that the job is complete + } else { //We need to send a subaddress + I2C_GenerateSTART(I2Cx, ENABLE); //program the repeated Start + subaddress_sent = 1; //this is set back to zero upon completion of the current task + } + } + //we must wait for the start to clear, otherwise we get constant BTF + while (I2Cx->CR1 & 0x0100) { ; } + } else if (SReg_1 & 0x0040) { //Byte received - EV7 + read_p[index++] = I2C_ReceiveData(I2Cx); + if (bytes == (index + 3)) + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush so we can get an EV7_2 + if (bytes == index) //We have completed a final EV7 + index++; //to show job is complete + } else if (SReg_1 & 0x0080) { //Byte transmitted -EV8/EV8_1 + if (index != -1) { //we dont have a subaddress to send + I2C_SendData(I2Cx, write_p[index++]); + if (bytes == index) //we have sent all the data + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush + } else { + index++; + I2C_SendData(I2Cx, reg); //send the subaddress + if (reading || !bytes) //if receiving or sending 0 bytes, flush now + I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush + } + } + if (index == bytes + 1) { //we have completed the current job + //Completion Tasks go here + //End of completion tasks + subaddress_sent = 0; //reset this here + // I2Cx->CR1 &= ~0x0800; //reset the POS bit so NACK applied to the current byte + if (final_stop) //If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Disable EVT and ERR interrupts while bus inactive + busy = 0; + } +} + +void i2cInit(I2C_TypeDef *I2C) +{ + NVIC_InitTypeDef NVIC_InitStructure; + GPIO_InitTypeDef GPIO_InitStructure; + I2C_InitTypeDef I2C_InitStructure; + + // Init pins + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + I2Cx = I2C; + + // clock out stuff to make sure slaves arent stuck + i2cUnstick(); + + // Init I2C + I2C_DeInit(I2Cx); + I2C_StructInit(&I2C_InitStructure); + + I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Enable EVT and ERR interrupts - they are enabled by the first request + I2C_InitStructure.I2C_Mode = I2C_Mode_I2C; + I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2; + I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; + I2C_InitStructure.I2C_ClockSpeed = 400000; + I2C_Cmd(I2Cx, ENABLE); + I2C_Init(I2Cx, &I2C_InitStructure); + + NVIC_PriorityGroupConfig(0x500); + + // I2C ER Interrupt + NVIC_InitStructure.NVIC_IRQChannel = I2C2_ER_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + // I2C EV Interrupt + NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_Init(&NVIC_InitStructure); + +} + +uint16_t i2cGetErrorCounter(void) +{ + return i2cErrorCount; +} + +static void i2cUnstick(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + uint8_t i; + + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + GPIO_SetBits(GPIOB, GPIO_Pin_10 | GPIO_Pin_11); + for (i = 0; i < 8; i++) { + // Wait for any clock stretching to finish + while (!GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_10)) + delayMicroseconds(10); + + // Pull low + GPIO_ResetBits(GPIOB, GPIO_Pin_10); //Set bus low + delayMicroseconds(10); + // Release high again + GPIO_SetBits(GPIOB, GPIO_Pin_10); //Set bus high + delayMicroseconds(10); + } + + // Generate a start then stop condition + // SCL PB10 + // SDA PB11 + + GPIO_ResetBits(GPIOB, GPIO_Pin_11); // Set bus data low + delayMicroseconds(10); + GPIO_ResetBits(GPIOB, GPIO_Pin_10); // Set bus scl low + delayMicroseconds(10); + GPIO_SetBits(GPIOB, GPIO_Pin_10); // Set bus scl high + delayMicroseconds(10); + GPIO_SetBits(GPIOB, GPIO_Pin_11); // Set bus sda high + + // Init pins + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD; + GPIO_Init(GPIOB, &GPIO_InitStructure); +} + +#endif diff --git a/src/baseflight/src/drv_i2c.h b/src/baseflight/src/drv_i2c.h new file mode 100755 index 0000000000..1a9fe114d8 --- /dev/null +++ b/src/baseflight/src/drv_i2c.h @@ -0,0 +1,7 @@ +#pragma once + +void i2cInit(I2C_TypeDef *I2Cx); +bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data); +bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data); +bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf); +uint16_t i2cGetErrorCounter(void); diff --git a/src/baseflight/src/drv_i2c_soft.c b/src/baseflight/src/drv_i2c_soft.c new file mode 100644 index 0000000000..bc03ee5e40 --- /dev/null +++ b/src/baseflight/src/drv_i2c_soft.c @@ -0,0 +1,215 @@ +#include "board.h" + +// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled. +// SCL PB10 +// SDA PB11 + + +#ifdef SOFT_I2C + +#define SCL_H GPIOB->BSRR = GPIO_Pin_10 /* GPIO_SetBits(GPIOB , GPIO_Pin_10) */ +#define SCL_L GPIOB->BRR = GPIO_Pin_10 /* GPIO_ResetBits(GPIOB , GPIO_Pin_10) */ + +#define SDA_H GPIOB->BSRR = GPIO_Pin_11 /* GPIO_SetBits(GPIOB , GPIO_Pin_11) */ +#define SDA_L GPIOB->BRR = GPIO_Pin_11 /* GPIO_ResetBits(GPIOB , GPIO_Pin_11) */ + +#define SCL_read (GPIOB->IDR & GPIO_Pin_10) /* GPIO_ReadInputDataBit(GPIOB , GPIO_Pin_10) */ +#define SDA_read (GPIOB->IDR & GPIO_Pin_11) /* GPIO_ReadInputDataBit(GPIOB , GPIO_Pin_11) */ + +static void I2C_delay(void) +{ + volatile int i = 7; + while (i) + i--; +} + +static bool I2C_Start(void) +{ + SDA_H; + SCL_H; + I2C_delay(); + if (!SDA_read) + return false; + SDA_L; + I2C_delay(); + if (SDA_read) + return false; + SDA_L; + I2C_delay(); + return true; +} + +static void I2C_Stop(void) +{ + SCL_L; + I2C_delay(); + SDA_L; + I2C_delay(); + SCL_H; + I2C_delay(); + SDA_H; + I2C_delay(); +} + +static void I2C_Ack(void) +{ + SCL_L; + I2C_delay(); + SDA_L; + I2C_delay(); + SCL_H; + I2C_delay(); + SCL_L; + I2C_delay(); +} + +static void I2C_NoAck(void) +{ + SCL_L; + I2C_delay(); + SDA_H; + I2C_delay(); + SCL_H; + I2C_delay(); + SCL_L; + I2C_delay(); +} + +static bool I2C_WaitAck(void) +{ + SCL_L; + I2C_delay(); + SDA_H; + I2C_delay(); + SCL_H; + I2C_delay(); + if (SDA_read) { + SCL_L; + return false; + } + SCL_L; + return true; +} + +static void I2C_SendByte(uint8_t byte) +{ + uint8_t i = 8; + while (i--) { + SCL_L; + I2C_delay(); + if (byte & 0x80) + SDA_H; + else + SDA_L; + byte <<= 1; + I2C_delay(); + SCL_H; + I2C_delay(); + } + SCL_L; +} + +static uint8_t I2C_ReceiveByte(void) +{ + uint8_t i = 8; + uint8_t byte = 0; + + SDA_H; + while (i--) { + byte <<= 1; + SCL_L; + I2C_delay(); + SCL_H; + I2C_delay(); + if (SDA_read) { + byte |= 0x01; + } + } + SCL_L; + return byte; +} + +void i2cInit(I2C_TypeDef * I2C) +{ + GPIO_InitTypeDef gpio; + + gpio.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11; + gpio.GPIO_Speed = GPIO_Speed_2MHz; + gpio.GPIO_Mode = GPIO_Mode_Out_OD; + GPIO_Init(GPIOB, &gpio); +} + +bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data) +{ + int i; + if (!I2C_Start()) + return false; + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + for (i = 0; i < len; i++) { + I2C_SendByte(data[i]); + if (!I2C_WaitAck()) { + I2C_Stop(); + return false; + } + } + I2C_Stop(); + return true; +} + +bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data) +{ + if (!I2C_Start()) + return false; + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + I2C_SendByte(data); + I2C_WaitAck(); + I2C_Stop(); + return true; +} + +bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf) +{ + if (!I2C_Start()) + return false; + I2C_SendByte(addr << 1 | I2C_Direction_Transmitter); + if (!I2C_WaitAck()) { + I2C_Stop(); + return false; + } + I2C_SendByte(reg); + I2C_WaitAck(); + I2C_Start(); + I2C_SendByte(addr << 1 | I2C_Direction_Receiver); + I2C_WaitAck(); + while (len) { + *buf = I2C_ReceiveByte(); + if (len == 1) + I2C_NoAck(); + else + I2C_Ack(); + buf++; + len--; + } + I2C_Stop(); + return true; +} + +uint16_t i2cGetErrorCounter(void) +{ + // TODO maybe fix this, but since this is test code, doesn't matter. + return 0; +} + +#endif diff --git a/src/baseflight/src/drv_l3g4200d.c b/src/baseflight/src/drv_l3g4200d.c new file mode 100644 index 0000000000..6cd09d01df --- /dev/null +++ b/src/baseflight/src/drv_l3g4200d.c @@ -0,0 +1,98 @@ +#include "board.h" + +// L3G4200D, Standard address 0x68 +#define L3G4200D_ADDRESS 0x68 +#define L3G4200D_ID 0xD3 + +// Registers +#define L3G4200D_WHO_AM_I 0x0F +#define L3G4200D_CTRL_REG1 0x20 +#define L3G4200D_CTRL_REG2 0x21 +#define L3G4200D_CTRL_REG3 0x22 +#define L3G4200D_CTRL_REG4 0x23 +#define L3G4200D_CTRL_REG5 0x24 +#define L3G4200D_REFERENCE 0x25 +#define L3G4200D_STATUS_REG 0x27 +#define L3G4200D_GYRO_OUT 0xA8 + +// Bits +#define L3G4200D_POWER_ON 0x0F +#define L3G4200D_FS_SEL_2000DPS 0xF0 +#define L3G4200D_DLPF_32HZ 0x00 +#define L3G4200D_DLPF_54HZ 0x40 +#define L3G4200D_DLPF_78HZ 0x80 +#define L3G4200D_DLPF_93HZ 0xC0 + +static uint8_t mpuLowPassFilter = L3G4200D_DLPF_32HZ; + +static void l3g4200dInit(void); +static void l3g4200dRead(int16_t *gyroData); +static void l3g4200dAlign(int16_t *gyroData); + +bool l3g4200dDetect(sensor_t *gyro) +{ + uint8_t deviceid; + + delay(25); + + i2cRead(L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid); + if (deviceid != L3G4200D_ID) + return false; + + gyro->init = l3g4200dInit; + gyro->read = l3g4200dRead; + gyro->align = l3g4200dAlign; + + return true; +} + +void l3g4200dConfig(uint16_t lpf) +{ + switch (lpf) { + case 32: + mpuLowPassFilter = L3G4200D_DLPF_32HZ; + break; + case 54: + mpuLowPassFilter = L3G4200D_DLPF_54HZ; + break; + case 78: + mpuLowPassFilter = L3G4200D_DLPF_78HZ; + break; + case 93: + mpuLowPassFilter = L3G4200D_DLPF_93HZ; + break; + } + + i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter); +} + +static void l3g4200dInit(void) +{ + bool ack; + + delay(100); + + ack = i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS); + if (!ack) + failureMode(3); + + delay(5); + i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter); +} + +static void l3g4200dAlign(int16_t *gyroData) +{ + gyroData[0] = -gyroData[0]; + gyroData[1] = gyroData[1]; + gyroData[2] = -gyroData[2]; +} + +// Read 3 gyro values into user-provided buffer. No overrun checking is done. +static void l3g4200dRead(int16_t *gyroData) +{ + uint8_t buf[6]; + i2cRead(L3G4200D_ADDRESS, L3G4200D_GYRO_OUT, 6, buf); + gyroData[1] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + gyroData[0] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; +} diff --git a/src/baseflight/src/drv_l3g4200d.h b/src/baseflight/src/drv_l3g4200d.h new file mode 100644 index 0000000000..7c8d0a338b --- /dev/null +++ b/src/baseflight/src/drv_l3g4200d.h @@ -0,0 +1,4 @@ +#pragma once + +bool l3g4200dDetect(sensor_t * gyro); +void l3g4200dConfig(uint16_t lpf); diff --git a/src/baseflight/src/drv_ledring.c b/src/baseflight/src/drv_ledring.c new file mode 100644 index 0000000000..fba6f1b0a1 --- /dev/null +++ b/src/baseflight/src/drv_ledring.c @@ -0,0 +1,53 @@ +#include "board.h" +#include "mw.h" + +// Driver for DFRobot I2C Led Ring +#define LED_RING_ADDRESS 0x6D + +bool ledringDetect(void) +{ + bool ack = false; + uint8_t sig = 'e'; + + ack = i2cWrite(LED_RING_ADDRESS, 0xFF, sig); + if (!ack) + return false; + return true; +} + +void ledringState(void) +{ + uint8_t b[10]; + static uint8_t state; + + if (state == 0) { + b[0] = 'z'; + b[1] = (180 - heading) / 2; // 1 unit = 2 degrees; + i2cWriteBuffer(LED_RING_ADDRESS, 0xFF, 2, b); + state = 1; + } else if (state == 1) { + b[0] = 'y'; + b[1] = constrain(angle[ROLL] / 10 + 90, 0, 180); + b[2] = constrain(angle[PITCH] / 10 + 90, 0, 180); + i2cWriteBuffer(LED_RING_ADDRESS, 0xFF, 3, b); + state = 2; + } else if (state == 2) { + b[0] = 'd'; // all unicolor GREEN + b[1] = 1; + if (f.ARMED) + b[2] = 1; + else + b[2] = 0; + i2cWriteBuffer(LED_RING_ADDRESS, 0xFF, 3, b); + state = 0; + } +} + +void ledringBlink(void) +{ + uint8_t b[3]; + b[0] = 'k'; + b[1] = 10; + b[2] = 10; + i2cWriteBuffer(LED_RING_ADDRESS, 0xFF, 3, b); +} diff --git a/src/baseflight/src/drv_ledring.h b/src/baseflight/src/drv_ledring.h new file mode 100644 index 0000000000..579f0ba250 --- /dev/null +++ b/src/baseflight/src/drv_ledring.h @@ -0,0 +1,5 @@ +#pragma once + +bool ledringDetect(void); +void ledringState(void); +void ledringBlink(void); diff --git a/src/baseflight/src/drv_mma845x.c b/src/baseflight/src/drv_mma845x.c new file mode 100644 index 0000000000..6affd61d2a --- /dev/null +++ b/src/baseflight/src/drv_mma845x.c @@ -0,0 +1,110 @@ +#include "board.h" + +// MMA8452QT, Standard address 0x1C +// ACC_INT2 routed to PA5 + +#define MMA8452_ADDRESS 0x1C + +#define MMA8452_DEVICE_SIGNATURE 0x2A +#define MMA8451_DEVICE_SIGNATURE 0x1A + +#define MMA8452_STATUS 0x00 +#define MMA8452_OUT_X_MSB 0x01 +#define MMA8452_WHO_AM_I 0x0D +#define MMA8452_XYZ_DATA_CFG 0x0E +#define MMA8452_HP_FILTER_CUTOFF 0x0F +#define MMA8452_CTRL_REG1 0x2A +#define MMA8452_CTRL_REG2 0x2B +#define MMA8452_CTRL_REG3 0x2C +#define MMA8452_CTRL_REG4 0x2D +#define MMA8452_CTRL_REG5 0x2E + +#define MMA8452_FS_RANGE_8G 0x02 +#define MMA8452_FS_RANGE_4G 0x01 +#define MMA8452_FS_RANGE_2G 0x00 + +#define MMA8452_HPF_CUTOFF_LV1 0x00 +#define MMA8452_HPF_CUTOFF_LV2 0x01 +#define MMA8452_HPF_CUTOFF_LV3 0x02 +#define MMA8452_HPF_CUTOFF_LV4 0x03 + +#define MMA8452_CTRL_REG2_B7_ST 0x80 +#define MMA8452_CTRL_REG2_B6_RST 0x40 +#define MMA8452_CTRL_REG2_B4_SMODS1 0x10 +#define MMA8452_CTRL_REG2_B3_SMODS0 0x08 +#define MMA8452_CTRL_REG2_B2_SLPE 0x04 +#define MMA8452_CTRL_REG2_B1_MODS1 0x02 +#define MMA8452_CTRL_REG2_B0_MODS0 0x01 + +#define MMA8452_CTRL_REG2_MODS_LP 0x03 +#define MMA8452_CTRL_REG2_MODS_HR 0x02 +#define MMA8452_CTRL_REG2_MODS_LNLP 0x01 +#define MMA8452_CTRL_REG2_MODS_NOR 0x00 + +#define MMA8452_CTRL_REG3_IPOL 0x02 +#define MMA8452_CTRL_REG4_INT_EN_DRDY 0x01 + +#define MMA8452_CTRL_REG1_LNOISE 0x04 +#define MMA8452_CTRL_REG1_ACTIVE 0x01 + +extern uint16_t acc_1G; +static uint8_t device_id; + +static void mma8452Init(void); +static void mma8452Read(int16_t *accelData); +static void mma8452Align(int16_t *accelData); + +bool mma8452Detect(sensor_t *acc) +{ + bool ack = false; + uint8_t sig = 0; + + ack = i2cRead(MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig); + if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE)) + return false; + + acc->init = mma8452Init; + acc->read = mma8452Read; + acc->align = mma8452Align; + device_id = sig; + return true; +} + +static void mma8452Init(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + // PA5 - ACC_INT2 output on rev3/4 hardware + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff + i2cWrite(MMA8452_ADDRESS, MMA8452_XYZ_DATA_CFG, MMA8452_FS_RANGE_8G); + i2cWrite(MMA8452_ADDRESS, MMA8452_HP_FILTER_CUTOFF, MMA8452_HPF_CUTOFF_LV4); + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG2, MMA8452_CTRL_REG2_MODS_HR | MMA8452_CTRL_REG2_MODS_HR << 3); // High resolution measurement in both sleep and active modes + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH) + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver) + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2 + i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, MMA8452_CTRL_REG1_LNOISE | MMA8452_CTRL_REG1_ACTIVE); // Turn on measurements, low noise at max scale mode, Data Rate 800Hz. LNoise mode makes range +-4G. + + acc_1G = 256; +} + +static void mma8452Read(int16_t *accelData) +{ + uint8_t buf[6]; + + i2cRead(MMA8452_ADDRESS, MMA8452_OUT_X_MSB, 6, buf); + accelData[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4; + accelData[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4; + accelData[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4; +} + +static void mma8452Align(int16_t *accelData) +{ + accelData[0] = -accelData[0]; + accelData[1] = -accelData[1]; + accelData[2] = accelData[2]; +} diff --git a/src/baseflight/src/drv_mma845x.h b/src/baseflight/src/drv_mma845x.h new file mode 100644 index 0000000000..8b33544179 --- /dev/null +++ b/src/baseflight/src/drv_mma845x.h @@ -0,0 +1,3 @@ +#pragma once + +bool mma8452Detect(sensor_t *acc); diff --git a/src/baseflight/src/drv_mpu3050.c b/src/baseflight/src/drv_mpu3050.c new file mode 100755 index 0000000000..8aca692c99 --- /dev/null +++ b/src/baseflight/src/drv_mpu3050.c @@ -0,0 +1,118 @@ +#include "board.h" + +// MPU3050, Standard address 0x68 +#define MPU3050_ADDRESS 0x68 + +// Registers +#define MPU3050_SMPLRT_DIV 0x15 +#define MPU3050_DLPF_FS_SYNC 0x16 +#define MPU3050_INT_CFG 0x17 +#define MPU3050_TEMP_OUT 0x1B +#define MPU3050_GYRO_OUT 0x1D +#define MPU3050_USER_CTRL 0x3D +#define MPU3050_PWR_MGM 0x3E + +// Bits +#define MPU3050_FS_SEL_2000DPS 0x18 +#define MPU3050_DLPF_10HZ 0x05 +#define MPU3050_DLPF_20HZ 0x04 +#define MPU3050_DLPF_42HZ 0x03 +#define MPU3050_DLPF_98HZ 0x02 +#define MPU3050_DLPF_188HZ 0x01 +#define MPU3050_DLPF_256HZ 0x00 + +#define MPU3050_USER_RESET 0x01 +#define MPU3050_CLK_SEL_PLL_GX 0x01 + +static uint8_t mpuLowPassFilter = MPU3050_DLPF_42HZ; + +static void mpu3050Init(void); +static void mpu3050Read(int16_t *gyroData); +static void mpu3050Align(int16_t *gyroData); +static void mpu3050ReadTemp(int16_t *tempData); + +bool mpu3050Detect(sensor_t *gyro) +{ + bool ack; + + delay(25); // datasheet page 13 says 20ms. other stuff could have been running meanwhile. but we'll be safe + + ack = i2cWrite(MPU3050_ADDRESS, MPU3050_SMPLRT_DIV, 0); + if (!ack) + return false; + + gyro->init = mpu3050Init; + gyro->read = mpu3050Read; + gyro->align = mpu3050Align; + gyro->temperature = mpu3050ReadTemp; + + return true; +} + +void mpu3050Config(uint16_t lpf) +{ + switch (lpf) { + case 256: + mpuLowPassFilter = MPU3050_DLPF_256HZ; + break; + case 188: + mpuLowPassFilter = MPU3050_DLPF_188HZ; + break; + case 98: + mpuLowPassFilter = MPU3050_DLPF_98HZ; + break; + case 42: + mpuLowPassFilter = MPU3050_DLPF_42HZ; + break; + case 20: + mpuLowPassFilter = MPU3050_DLPF_20HZ; + break; + case 10: + mpuLowPassFilter = MPU3050_DLPF_10HZ; + break; + } + + i2cWrite(MPU3050_ADDRESS, MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | mpuLowPassFilter); +} + +static void mpu3050Init(void) +{ + bool ack; + + delay(25); // datasheet page 13 says 20ms. other stuff could have been running meanwhile. but we'll be safe + + ack = i2cWrite(MPU3050_ADDRESS, MPU3050_SMPLRT_DIV, 0); + if (!ack) + failureMode(3); + + i2cWrite(MPU3050_ADDRESS, MPU3050_DLPF_FS_SYNC, MPU3050_FS_SEL_2000DPS | mpuLowPassFilter); + i2cWrite(MPU3050_ADDRESS, MPU3050_INT_CFG, 0); + i2cWrite(MPU3050_ADDRESS, MPU3050_USER_CTRL, MPU3050_USER_RESET); + i2cWrite(MPU3050_ADDRESS, MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX); +} + +static void mpu3050Align(int16_t *gyroData) +{ + // official direction is RPY + gyroData[0] = gyroData[0]; + gyroData[1] = gyroData[1]; + gyroData[2] = -gyroData[2]; +} + +// Read 3 gyro values into user-provided buffer. No overrun checking is done. +static void mpu3050Read(int16_t *gyroData) +{ + uint8_t buf[6]; + i2cRead(MPU3050_ADDRESS, MPU3050_GYRO_OUT, 6, buf); + gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; +} + +static void mpu3050ReadTemp(int16_t *tempData) +{ + uint8_t buf[2]; + i2cRead(MPU3050_ADDRESS, MPU3050_TEMP_OUT, 2, buf); + + *tempData = 35 + ((int32_t)(buf[0] << 8 | buf[1]) + 13200) / 280; +} diff --git a/src/baseflight/src/drv_mpu3050.h b/src/baseflight/src/drv_mpu3050.h new file mode 100755 index 0000000000..1ae321e239 --- /dev/null +++ b/src/baseflight/src/drv_mpu3050.h @@ -0,0 +1,4 @@ +#pragma once + +bool mpu3050Detect(sensor_t *gyro); +void mpu3050Config(uint16_t lpf); diff --git a/src/baseflight/src/drv_mpu6050.c b/src/baseflight/src/drv_mpu6050.c new file mode 100644 index 0000000000..e7c644df96 --- /dev/null +++ b/src/baseflight/src/drv_mpu6050.c @@ -0,0 +1,763 @@ +#include "board.h" + +// MPU6050, Standard address 0x68 +// MPU_INT on PB13 on rev4 hardware +#define MPU6050_ADDRESS 0x68 + +// Experimental DMP support +// #define MPU6050_DMP + +#define DMP_MEM_START_ADDR 0x6E +#define DMP_MEM_R_W 0x6F + +#define INV_MAX_NUM_ACCEL_SAMPLES (8) +#define DMP_REF_QUATERNION (0) +#define DMP_REF_GYROS (DMP_REF_QUATERNION + 4) // 4 +#define DMP_REF_CONTROL (DMP_REF_GYROS + 3) // 7 +#define DMP_REF_RAW (DMP_REF_CONTROL + 4) // 11 +#define DMP_REF_RAW_EXTERNAL (DMP_REF_RAW + 8) // 19 +#define DMP_REF_ACCEL (DMP_REF_RAW_EXTERNAL + 6) // 25 +#define DMP_REF_QUANT_ACCEL (DMP_REF_ACCEL + 3) // 28 +#define DMP_REF_QUATERNION_6AXIS (DMP_REF_QUANT_ACCEL + INV_MAX_NUM_ACCEL_SAMPLES) // 36 +#define DMP_REF_EIS (DMP_REF_QUATERNION_6AXIS + 4) // 40 +#define DMP_REF_DMP_PACKET (DMP_REF_EIS + 3) // 43 +#define DMP_REF_GARBAGE (DMP_REF_DMP_PACKET + 1) // 44 +#define DMP_REF_LAST (DMP_REF_GARBAGE + 1) // 45 + +#define MPU_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN +#define MPU_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN +#define MPU_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN +#define MPU_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS +#define MPU_RA_XA_OFFS_L_TC 0x07 +#define MPU_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS +#define MPU_RA_YA_OFFS_L_TC 0x09 +#define MPU_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS +#define MPU_RA_ZA_OFFS_L_TC 0x0B +#define MPU_RA_PRODUCT_ID 0x0C // Product ID Register +#define MPU_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR +#define MPU_RA_XG_OFFS_USRL 0x14 +#define MPU_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR +#define MPU_RA_YG_OFFS_USRL 0x16 +#define MPU_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR +#define MPU_RA_ZG_OFFS_USRL 0x18 +#define MPU_RA_SMPLRT_DIV 0x19 +#define MPU_RA_CONFIG 0x1A +#define MPU_RA_GYRO_CONFIG 0x1B +#define MPU_RA_ACCEL_CONFIG 0x1C +#define MPU_RA_FF_THR 0x1D +#define MPU_RA_FF_DUR 0x1E +#define MPU_RA_MOT_THR 0x1F +#define MPU_RA_MOT_DUR 0x20 +#define MPU_RA_ZRMOT_THR 0x21 +#define MPU_RA_ZRMOT_DUR 0x22 +#define MPU_RA_FIFO_EN 0x23 +#define MPU_RA_I2C_MST_CTRL 0x24 +#define MPU_RA_I2C_SLV0_ADDR 0x25 +#define MPU_RA_I2C_SLV0_REG 0x26 +#define MPU_RA_I2C_SLV0_CTRL 0x27 +#define MPU_RA_I2C_SLV1_ADDR 0x28 +#define MPU_RA_I2C_SLV1_REG 0x29 +#define MPU_RA_I2C_SLV1_CTRL 0x2A +#define MPU_RA_I2C_SLV2_ADDR 0x2B +#define MPU_RA_I2C_SLV2_REG 0x2C +#define MPU_RA_I2C_SLV2_CTRL 0x2D +#define MPU_RA_I2C_SLV3_ADDR 0x2E +#define MPU_RA_I2C_SLV3_REG 0x2F +#define MPU_RA_I2C_SLV3_CTRL 0x30 +#define MPU_RA_I2C_SLV4_ADDR 0x31 +#define MPU_RA_I2C_SLV4_REG 0x32 +#define MPU_RA_I2C_SLV4_DO 0x33 +#define MPU_RA_I2C_SLV4_CTRL 0x34 +#define MPU_RA_I2C_SLV4_DI 0x35 +#define MPU_RA_I2C_MST_STATUS 0x36 +#define MPU_RA_INT_PIN_CFG 0x37 +#define MPU_RA_INT_ENABLE 0x38 +#define MPU_RA_DMP_INT_STATUS 0x39 +#define MPU_RA_INT_STATUS 0x3A +#define MPU_RA_ACCEL_XOUT_H 0x3B +#define MPU_RA_ACCEL_XOUT_L 0x3C +#define MPU_RA_ACCEL_YOUT_H 0x3D +#define MPU_RA_ACCEL_YOUT_L 0x3E +#define MPU_RA_ACCEL_ZOUT_H 0x3F +#define MPU_RA_ACCEL_ZOUT_L 0x40 +#define MPU_RA_TEMP_OUT_H 0x41 +#define MPU_RA_TEMP_OUT_L 0x42 +#define MPU_RA_GYRO_XOUT_H 0x43 +#define MPU_RA_GYRO_XOUT_L 0x44 +#define MPU_RA_GYRO_YOUT_H 0x45 +#define MPU_RA_GYRO_YOUT_L 0x46 +#define MPU_RA_GYRO_ZOUT_H 0x47 +#define MPU_RA_GYRO_ZOUT_L 0x48 +#define MPU_RA_EXT_SENS_DATA_00 0x49 +#define MPU_RA_MOT_DETECT_STATUS 0x61 +#define MPU_RA_I2C_SLV0_DO 0x63 +#define MPU_RA_I2C_SLV1_DO 0x64 +#define MPU_RA_I2C_SLV2_DO 0x65 +#define MPU_RA_I2C_SLV3_DO 0x66 +#define MPU_RA_I2C_MST_DELAY_CTRL 0x67 +#define MPU_RA_SIGNAL_PATH_RESET 0x68 +#define MPU_RA_MOT_DETECT_CTRL 0x69 +#define MPU_RA_USER_CTRL 0x6A +#define MPU_RA_PWR_MGMT_1 0x6B +#define MPU_RA_PWR_MGMT_2 0x6C +#define MPU_RA_BANK_SEL 0x6D +#define MPU_RA_MEM_START_ADDR 0x6E +#define MPU_RA_MEM_R_W 0x6F +#define MPU_RA_DMP_CFG_1 0x70 +#define MPU_RA_DMP_CFG_2 0x71 +#define MPU_RA_FIFO_COUNTH 0x72 +#define MPU_RA_FIFO_COUNTL 0x73 +#define MPU_RA_FIFO_R_W 0x74 +#define MPU_RA_WHO_AM_I 0x75 + +#define MPU6050_SMPLRT_DIV 0 //8000Hz +// #define MPU6050_DLPF_CFG 0 // 256Hz +#define MPU6050_DLPF_CFG 3 // 42Hz + +#define MPU6000ES_REV_C4 0x14 +#define MPU6000ES_REV_C5 0x15 +#define MPU6000ES_REV_D6 0x16 +#define MPU6000ES_REV_D7 0x17 +#define MPU6000ES_REV_D8 0x18 +#define MPU6000_REV_C4 0x54 +#define MPU6000_REV_C5 0x55 +#define MPU6000_REV_D6 0x56 +#define MPU6000_REV_D7 0x57 +#define MPU6000_REV_D8 0x58 +#define MPU6000_REV_D9 0x59 + +static void mpu6050AccInit(void); +static void mpu6050AccRead(int16_t * accData); +static void mpu6050AccAlign(int16_t * accData); +static void mpu6050GyroInit(void); +static void mpu6050GyroRead(int16_t * gyroData); +static void mpu6050GyroAlign(int16_t * gyroData); + +#ifdef MPU6050_DMP +static void mpu6050DmpInit(void); +float dmpdata[2]; +int16_t dmpGyroData[3]; +#endif + +extern uint16_t acc_1G; +uint8_t mpuProductID = 0; + +bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t scale) +{ + bool ack; + uint8_t sig; + + delay(35); // datasheet page 13 says 30ms. other stuff could have been running meanwhile. but we'll be safe + + ack = i2cRead(MPU6050_ADDRESS, MPU_RA_WHO_AM_I, 1, &sig); + if (!ack) + return false; + + // So like, MPU6xxx has a "WHO_AM_I" register, that is used to verify the identity of the device. + // The contents of WHO_AM_I are the upper 6 bits of the MPU-60X0’s 7-bit I2C address. + // The least significant bit of the MPU-60X0’s I2C address is determined by the value of the AD0 pin. (we know that already). + // But here's the best part: The value of the AD0 pin is not reflected in this register. + if (sig != (MPU6050_ADDRESS & 0x7e)) + return false; + + // get chip revision + fake it if needed + if (scale) + mpuProductID = MPU6000_REV_C5; // no, seriously? why don't you make the chip ID list public. + else + i2cRead(MPU6050_ADDRESS, MPU_RA_PRODUCT_ID, 1, &mpuProductID); + + acc->init = mpu6050AccInit; + acc->read = mpu6050AccRead; + acc->align = mpu6050AccAlign; + gyro->init = mpu6050GyroInit; + gyro->read = mpu6050GyroRead; + gyro->align = mpu6050GyroAlign; + +#ifdef MPU6050_DMP + mpu6050DmpInit(); +#endif + + return true; +} + +static void mpu6050AccInit(void) +{ + acc_1G = 1023; +} + +static void mpu6050AccRead(int16_t *accData) +{ + uint8_t buf[6]; + +#ifndef MPU6050_DMP + i2cRead(MPU6050_ADDRESS, MPU_RA_ACCEL_XOUT_H, 6, buf); + accData[0] = (int16_t)((buf[0] << 8) | buf[1]) / 8; + accData[1] = (int16_t)((buf[2] << 8) | buf[3]) / 8; + accData[2] = (int16_t)((buf[4] << 8) | buf[5]) / 8; +#else + accData[0] = accData[1] = accData[2] = 0; +#endif +} + +static void mpu6050AccAlign(int16_t *accData) +{ + int16_t temp[2]; + temp[0] = accData[0]; + temp[1] = accData[1]; + + // official direction is RPY + accData[0] = temp[1]; + accData[1] = -temp[0]; + accData[2] = accData[2]; +} + +static void mpu6050GyroInit(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + // PB13 - MPU_INT output on rev4 hardware + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOB, &GPIO_InitStructure); + +#ifndef MPU6050_DMP + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1 + delay(5); + i2cWrite(MPU6050_ADDRESS, MPU_RA_SMPLRT_DIV, 0x00); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference) + i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 0 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_PIN_CFG -- INT_LEVEL_HIGH, INT_OPEN_DIS, LATCH_INT_DIS, INT_RD_CLEAR_DIS, FSYNC_INT_LEVEL_HIGH, FSYNC_INT_DIS, I2C_BYPASS_EN, CLOCK_DIS + i2cWrite(MPU6050_ADDRESS, MPU_RA_CONFIG, MPU6050_DLPF_CFG); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz) + i2cWrite(MPU6050_ADDRESS, MPU_RA_GYRO_CONFIG, 0x18); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec + + // ACC Init stuff. Moved into gyro init because the reset above would screw up accel config. Oops. + // Product ID detection code from eosBandi (or rather, DIYClones). This doesn't cover product ID for MPU6050 as far as I can tell + if ((mpuProductID == MPU6000ES_REV_C4) || (mpuProductID == MPU6000ES_REV_C5) || (mpuProductID == MPU6000_REV_C4) || (mpuProductID == MPU6000_REV_C5)) { + // Accel scale 8g (4096 LSB/g) + // Rev C has different scaling than rev D + i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 1 << 3); + } else { + i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 2 << 3); + } +#endif +} + +static void mpu6050GyroRead(int16_t * gyroData) +{ + uint8_t buf[6]; +#ifndef MPU6050_DMP + i2cRead(MPU6050_ADDRESS, MPU_RA_GYRO_XOUT_H, 6, buf); + gyroData[0] = (int16_t)((buf[0] << 8) | buf[1]) / 4; + gyroData[1] = (int16_t)((buf[2] << 8) | buf[3]) / 4; + gyroData[2] = (int16_t)((buf[4] << 8) | buf[5]) / 4; +#else + gyroData[0] = dmpGyroData[0] / 4 ; + gyroData[1] = dmpGyroData[1] / 4; + gyroData[2] = dmpGyroData[2] / 4; +#endif +} + +static void mpu6050GyroAlign(int16_t * gyroData) +{ + // official direction is RPY + gyroData[0] = gyroData[0]; + gyroData[1] = gyroData[1]; + gyroData[2] = -gyroData[2]; +} + +#ifdef MPU6050_DMP + +//This 3D array contains the default DMP memory bank binary that gets loaded during initialization. +//In the Invensense UC3-A3 firmware this is uploaded in 128 byte tranmissions, but the Arduino Wire +//library only supports 32 byte transmissions, including the register address to which you're writing, +//so I broke it up into 16 byte transmission payloads which are sent in the dmp_init() function below. +// +//This was reconstructed from observed I2C traffic generated by the UC3-A3 demo code, and not extracted +//directly from that code. That is true of all transmissions in this sketch, and any documentation has +//been added after the fact by referencing the Invensense code. + +const unsigned char dmpMem[8][16][16] = { + { + {0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00}, + {0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01}, + {0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01}, + {0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00}, + {0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00}, + {0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82}, + {0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00}, + {0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0}, + {0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC}, + {0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4}, + {0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10} + }, + { + {0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8}, + {0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7}, + {0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C}, + {0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C}, + {0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0} + }, + { + {0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00}, + {0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}, + {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00} + }, + { + {0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F}, + {0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2}, + {0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF}, + {0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C}, + {0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1}, + {0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01}, + {0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80}, + {0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C}, + {0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80}, + {0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E}, + {0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9}, + {0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24}, + {0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0}, + {0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86}, + {0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1}, + {0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86} + }, + { + {0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA}, + {0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C}, + {0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8}, + {0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3}, + {0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84}, + {0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5}, + {0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3}, + {0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1}, + {0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5}, + {0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D}, + {0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9}, + {0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D}, + {0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9}, + {0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A}, + {0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8}, + {0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87} + }, + { + {0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8}, + {0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68}, + {0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D}, + {0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94}, + {0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA}, + {0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56}, + {0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9}, + {0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA}, + {0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A}, + {0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60}, + {0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97}, + {0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04}, + {0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78}, + {0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79}, + {0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68}, + {0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68} + }, + { + {0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04}, + {0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66}, + {0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31}, + {0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60}, + {0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76}, + {0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56}, + {0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD}, + {0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91}, + {0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8}, + {0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE}, + {0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9}, + {0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD}, + {0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E}, + {0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8}, + {0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89}, + {0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79} + }, + { + {0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8}, + {0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA}, + {0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB}, + {0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3}, + {0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3}, + {0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3}, + {0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3}, + {0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC}, + {0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF} + } +}; + + +//DMP update transmissions (Bank, Start Address, Update Length, Update Data...) + +const uint8_t dmp_updates[29][9] = { + {0x03, 0x7B, 0x03, 0x4C, 0xCD, 0x6C}, //FCFG_1 inv_set_gyro_calibration + {0x03, 0xAB, 0x03, 0x36, 0x56, 0x76}, //FCFG_3 inv_set_gyro_calibration + {0x00, 0x68, 0x04, 0x02, 0xCB, 0x47, 0xA2}, //D_0_104 inv_set_gyro_calibration + {0x02, 0x18, 0x04, 0x00, 0x05, 0x8B, 0xC1}, //D_0_24 inv_set_gyro_calibration + {0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00}, //D_1_152 inv_set_accel_calibration + {0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97}, //FCFG_2 inv_set_accel_calibration + {0x03, 0x89, 0x03, 0x26, 0x46, 0x66}, //FCFG_7 inv_set_accel_calibration + {0x00, 0x6C, 0x02, 0x20, 0x00}, //D_0_108 inv_set_accel_calibration + {0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_00 inv_set_compass_calibration + {0x02, 0x44, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_01 + {0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_02 + {0x02, 0x4C, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_10 + {0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_11 + {0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_12 + {0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_20 + {0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_21 + {0x02, 0xBC, 0x04, 0x00, 0x00, 0x00, 0x00}, //CPASS_MTX_22 + {0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00}, //D_1_236 inv_apply_endian_accel + {0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97}, //FCFG_2 inv_set_mpu_sensors + {0x04, 0x02, 0x03, 0x0D, 0x35, 0x5D}, //CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion + {0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D}, //FCFG_5 inv_set_bias_update + {0x00, 0xA3, 0x01, 0x00}, //D_0_163 inv_set_dead_zone + //SET INT_ENABLE at i=22 + {0x07, 0x86, 0x01, 0xFE}, //CFG_6 inv_set_fifo_interupt + {0x07, 0x41, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38}, //CFG_8 inv_send_quaternion + {0x07, 0x7E, 0x01, 0x30}, //CFG_16 inv_set_footer + {0x07, 0x46, 0x01, 0x9A}, //CFG_GYRO_SOURCE inv_send_gyro + {0x07, 0x47, 0x04, 0xF1, 0x28, 0x30, 0x38}, //CFG_9 inv_send_gyro -> inv_construct3_fifo + {0x07, 0x6C, 0x04, 0xF1, 0x28, 0x30, 0x38}, //CFG_12 inv_send_accel -> inv_construct3_fifo + {0x02, 0x16, 0x02, 0x00, 0x00}, //D_0_22 inv_set_fifo_rate +}; + +static long dmp_lastRead = 0; +static uint8_t dmp_processed_packet[8]; +static uint8_t dmp_received_packet[50]; +static uint8_t dmp_temp = 0; +uint8_t dmp_fifoCountL = 0; +static uint8_t dmp_fifoCountL2 = 0; +static uint8_t dmp_packetCount = 0x00; +static bool dmp_longPacket = false; +static bool dmp_firstPacket = true; + +static void mpu6050DmpMemInit(void); +static void mpu6050DmpBankSelect(uint8_t bank); +static bool mpu6050DmpFifoReady(void); +static void mpu6050DmpGetPacket(void); +static void mpu6050DmpProcessQuat(void); +void mpu6050DmpResetFifo(void); + +static void mpu6050DmpInit(void) +{ + uint8_t temp = 0; + + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0xC0); // device reset + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 0x00); + delay(10); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_BANK_SEL, 0x70); + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x06); + i2cRead(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 1, &temp); + i2cWrite(MPU6050_ADDRESS, MPU_RA_BANK_SEL, 0x00); + + /* + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_XG_OFFS_TC); + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_YG_OFFS_TC); + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_ZG_OFFS_TC); + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_USER_CTRL); + */ + + i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_PIN_CFG, 0x32); // I2C bypass enabled, latch int enabled, int read clear + i2cRead(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 1, &temp); + delay(5); + + mpu6050DmpMemInit(); +} + +void mpu6050DmpLoop(void) +{ + uint8_t temp; + uint8_t buf[2]; + + if (mpu6050DmpFifoReady()) { + LED1_ON; + mpu6050DmpGetPacket(); + + i2cRead(MPU6050_ADDRESS, MPU_RA_INT_STATUS, 1, &temp); + if (dmp_firstPacket) { + delay(1); + mpu6050DmpBankSelect(0x00); + + mpu6050DmpBankSelect(0x00); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x60); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 4, "\x04\x00\x00\x00"); // data + + mpu6050DmpBankSelect(0x01); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x62); + i2cRead(MPU6050_ADDRESS, DMP_MEM_R_W, 2, buf); + dmp_firstPacket = false; + mpu6050DmpFifoReady(); + } + + if (dmp_fifoCountL == 42) { + mpu6050DmpProcessQuat(); + } + LED1_OFF; + } +} + +#define dmp_quatTake32(a, b) (((a)[4*(b)+0]<<8) | ((a)[4*(b)+1]<<0)) +extern int16_t angle[2]; + +static void mpu6050DmpProcessQuat(void) +{ + float quat0, quat1, quat2, quat3; + int32_t quatl0, quatl1, quatl2, quatl3; + + quatl0 = dmp_quatTake32(dmp_received_packet, 0); + quatl1 = dmp_quatTake32(dmp_received_packet, 1); + quatl2 = dmp_quatTake32(dmp_received_packet, 2); + quatl3 = dmp_quatTake32(dmp_received_packet, 3); + + if (quatl0 > 32767) + quatl0 -= 65536; + if (quatl1 > 32767) + quatl1 -= 65536; + if (quatl2 > 32767) + quatl2 -= 65536; + if (quatl3 > 32767) + quatl3 -= 65536; + + quat0 = ((float) quatl0) / 16384.0f; + quat1 = ((float) quatl1) / 16384.0f; + quat2 = ((float) quatl2) / 16384.0f; + quat3 = ((float) quatl3) / 16384.0f; + + dmpdata[0] = atan2f(2 * ((quat0 * quat1) + (quat2 * quat3)), 1.0 - (2 * ((quat1 * quat1) + (quat2 * quat2)))) * (180.0f / M_PI); + dmpdata[1] = asinf(2 * ((quat0 * quat2) - (quat3 * quat1))) * (180.0f / M_PI); + angle[0] = dmpdata[0] * 10; + angle[1] = dmpdata[1] * 10; + + dmpGyroData[0] = ((dmp_received_packet[4 * 4 + 0] << 8) | (dmp_received_packet[4 * 4 + 1] << 0)); + dmpGyroData[1] = ((dmp_received_packet[4 * 5 + 0] << 8) | (dmp_received_packet[4 * 5 + 1] << 0)); + dmpGyroData[2] = ((dmp_received_packet[4 * 6 + 0] << 8) | (dmp_received_packet[4 * 6 + 1] << 0)); +} + +void mpu6050DmpResetFifo(void) +{ + uint8_t ctrl; + + i2cRead(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 1, &ctrl); + ctrl |= 0x04; + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, ctrl); +} + +static void mpu6050DmpGetPacket(void) +{ + if (dmp_fifoCountL > 32) { + dmp_fifoCountL2 = dmp_fifoCountL - 32; + dmp_longPacket = true; + } + + if (dmp_longPacket) { + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, 32, dmp_received_packet); + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, dmp_fifoCountL, dmp_received_packet + 32); + dmp_longPacket = false; + } else { + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, dmp_fifoCountL, dmp_received_packet); + } +} + +uint16_t dmpFifoLevel = 0; + +static bool mpu6050DmpFifoReady(void) +{ + uint8_t buf[2]; + + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_COUNTH, 2, buf); + + dmp_fifoCountL = buf[1]; + dmpFifoLevel = buf[0] << 8 | buf[1]; + + if (dmp_fifoCountL == 42 || dmp_fifoCountL == 44) + return true; + else { + // lame hack to empty out fifo, as dmpResetFifo doesn't actually seem to do it... + if (dmpFifoLevel > 100) { + // clear out fifo + uint8_t crap[16]; + do { + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, dmpFifoLevel > 16 ? 16 : dmpFifoLevel, crap); + i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_COUNTH, 2, buf); + dmpFifoLevel = buf[0] << 8 | buf[1]; + } while (dmpFifoLevel); + } + } + + return false; +} + +static void mpu6050DmpBankSelect(uint8_t bank) +{ + i2cWrite(MPU6050_ADDRESS, MPU_RA_BANK_SEL, bank); +} + +static void mpu6050DmpBankInit(void) +{ + uint8_t i, j; + uint8_t incoming[9]; + + for (i = 0; i < 7; i++) { + mpu6050DmpBankSelect(i); + for (j = 0; j < 16; j++) { + uint8_t start_addy = j * 0x10; + + i2cWrite(MPU6050_ADDRESS, DMP_MEM_START_ADDR, start_addy); + i2cWriteBuffer(MPU6050_ADDRESS, DMP_MEM_R_W, 16, (uint8_t *) & dmpMem[i][j][0]); + } + } + + mpu6050DmpBankSelect(7); + + for (j = 0; j < 8; j++) { + + uint8_t start_addy = j * 0x10; + + i2cWrite(MPU6050_ADDRESS, DMP_MEM_START_ADDR, start_addy); + i2cWriteBuffer(MPU6050_ADDRESS, DMP_MEM_R_W, 16, (uint8_t *) & dmpMem[7][j][0]); + } + + i2cWrite(MPU6050_ADDRESS, DMP_MEM_START_ADDR, 0x80); + i2cWriteBuffer(MPU6050_ADDRESS, DMP_MEM_R_W, 9, (uint8_t *) & dmpMem[7][8][0]); + + i2cRead(MPU6050_ADDRESS, DMP_MEM_R_W, 8, incoming); +} + + +static void mpu6050DmpMemInit(void) +{ + uint8_t i; + uint8_t temp; + + mpu6050DmpBankInit(); + + // Bank, Start Address, Update Length, Update Data... + for (i = 0; i < 22; i++) { + mpu6050DmpBankSelect(dmp_updates[i][0]); // bank + i2cWrite(MPU6050_ADDRESS, DMP_MEM_START_ADDR, dmp_updates[i][1]); // address + i2cWriteBuffer(MPU6050_ADDRESS, DMP_MEM_R_W, dmp_updates[i][2], (uint8_t *)&dmp_updates[i][3]); // data + } + + i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_ENABLE, 0x32); + + for (i = 22; i < 29; i++) { + mpu6050DmpBankSelect(dmp_updates[i][0]); // bank + i2cWrite(MPU6050_ADDRESS, DMP_MEM_START_ADDR, dmp_updates[i][1]); // address + i2cWriteBuffer(MPU6050_ADDRESS, DMP_MEM_R_W, dmp_updates[i][2], (uint8_t *)&dmp_updates[i][3]); // data + } + + /* + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_PWR_MGMT_1); + dmp_temp = i2c_readReg(MPU60X0_I2CADDR, MPU_RA_PWR_MGMT_2); + */ + + i2cWrite(MPU6050_ADDRESS, MPU_RA_INT_ENABLE, 0x02); // ?? + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); // CLKSEL = PLL w Z ref + i2cWrite(MPU6050_ADDRESS, MPU_RA_SMPLRT_DIV, 0x04); + i2cWrite(MPU6050_ADDRESS, MPU_RA_GYRO_CONFIG, 0x18); // full scale 2000 deg/s + i2cWrite(MPU6050_ADDRESS, MPU_RA_CONFIG, 0x0B); // ext_sync_set=temp_out_L, accel DLPF 44Hz, gyro DLPF 42Hz + i2cWrite(MPU6050_ADDRESS, MPU_RA_DMP_CFG_1, 0x03); + i2cWrite(MPU6050_ADDRESS, MPU_RA_DMP_CFG_2, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_XG_OFFS_TC, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_YG_OFFS_TC, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_ZG_OFFS_TC, 0x00); + + // clear offsets + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_XG_OFFS_USRH, 6, "\x00\x00\x00\x00\x00\x00"); // data + + mpu6050DmpBankSelect(0x01); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0xB2); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 2, "\xFF\xFF"); // data + + mpu6050DmpBankSelect(0x01); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x90); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 4, "\x09\x23\xA1\x35"); // data + + i2cRead(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 1, &temp); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 0x04); // fifo reset + + // Insert FIFO count read? + mpu6050DmpFifoReady(); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 0x00); // ?? I think this enables a lot of stuff but disables fifo + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x03); // CLKSEL = PLL w Z ref + delay(2); + + i2cRead(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 1, &temp); + i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 0x00); + i2cRead(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 1, &temp); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 0x00); // full scale range +/- 2g + delay(2); + i2cRead(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 1, &temp); + + i2cWrite(MPU6050_ADDRESS, MPU_RA_MOT_THR, 0x02); + i2cWrite(MPU6050_ADDRESS, MPU_RA_ZRMOT_THR, 0x9C); + i2cWrite(MPU6050_ADDRESS, MPU_RA_MOT_DUR, 0x50); + i2cWrite(MPU6050_ADDRESS, MPU_RA_ZRMOT_DUR, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 0x04); // fifo reset + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 0x00); + i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 0xC8); // fifo enable + + mpu6050DmpBankSelect(0x01); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x6A); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 2, "\x06\x00"); // data + + mpu6050DmpBankSelect(0x01); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x60); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 8, "\x00\x00\x00\x00\x00\x00\x00\x00"); // data + + mpu6050DmpBankSelect(0x00); // bank + i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x60); + i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 4, "\x40\x00\x00\x00"); // data +} + +#else /* MPU6050_DMP */ +void mpu6050DmpLoop(void) +{ + +} + +void mpu6050DmpResetFifo(void) +{ + +} +#endif /* MPU6050_DMP */ diff --git a/src/baseflight/src/drv_mpu6050.h b/src/baseflight/src/drv_mpu6050.h new file mode 100644 index 0000000000..6ce63ae98b --- /dev/null +++ b/src/baseflight/src/drv_mpu6050.h @@ -0,0 +1,5 @@ +#pragma once + +bool mpu6050Detect(sensor_t * acc, sensor_t * gyro, uint8_t scale); +void mpu6050DmpLoop(void); +void mpu6050DmpResetFifo(void); diff --git a/src/baseflight/src/drv_ms5611.c b/src/baseflight/src/drv_ms5611.c new file mode 100644 index 0000000000..b53e34a758 --- /dev/null +++ b/src/baseflight/src/drv_ms5611.c @@ -0,0 +1,180 @@ +#include "board.h" + +// MS5611, Standard address 0x77 +#define MS5611_ADDR 0x77 +// Autodetect: turn off BMP085 while initializing ms5611 and check PROM crc to confirm device +#define BMP085_OFF digitalLo(BARO_GPIO, BARO_PIN); +#define BMP085_ON digitalHi(BARO_GPIO, BARO_PIN); + +#define CMD_RESET 0x1E // ADC reset command +#define CMD_ADC_READ 0x00 // ADC read command +#define CMD_ADC_CONV 0x40 // ADC conversion command +#define CMD_ADC_D1 0x00 // ADC D1 conversion +#define CMD_ADC_D2 0x10 // ADC D2 conversion +#define CMD_ADC_256 0x00 // ADC OSR=256 +#define CMD_ADC_512 0x02 // ADC OSR=512 +#define CMD_ADC_1024 0x04 // ADC OSR=1024 +#define CMD_ADC_2048 0x06 // ADC OSR=2048 +#define CMD_ADC_4096 0x08 // ADC OSR=4096 +#define CMD_PROM_RD 0xA0 // Prom read command +#define PROM_NB 8 + +static void ms5611_reset(void); +static uint16_t ms5611_prom(int8_t coef_num); +static int8_t ms5611_crc(uint16_t *prom); +static uint32_t ms5611_read_adc(void); +static void ms5611_start_ut(void); +static void ms5611_get_ut(void); +static void ms5611_start_up(void); +static void ms5611_get_up(void); +static int32_t ms5611_calculate(void); + +static uint32_t ms5611_ut; // static result of temperature measurement +static uint32_t ms5611_up; // static result of pressure measurement +static uint16_t ms5611_c[PROM_NB]; // on-chip ROM +static uint8_t ms5611_osr = CMD_ADC_4096; + +bool ms5611Detect(baro_t *baro) +{ + GPIO_InitTypeDef GPIO_InitStructure; + bool ack = false; + uint8_t sig; + int i; + + // PC13 (BMP085's XCLR reset input, which we use to disable it) + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_Init(GPIOC, &GPIO_InitStructure); + BMP085_OFF; + + delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms + + // BMP085 is disabled. If we have a MS5611, it will reply. if no reply, means either + // we have BMP085 or no baro at all. + ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig); + if (!ack) + return false; + + ms5611_reset(); + // read all coefficients + for (i = 0; i < PROM_NB; i++) + ms5611_c[i] = ms5611_prom(i); + // check crc, bail out if wrong - we are probably talking to BMP085 w/o XCLR line! + if (ms5611_crc(ms5611_c) != 0) + return false; + + // TODO prom + CRC + baro->ut_delay = 10000; + baro->up_delay = 10000; + baro->repeat_delay = 4000; + baro->start_ut = ms5611_start_ut; + baro->get_ut = ms5611_get_ut; + baro->start_up = ms5611_start_up; + baro->get_up = ms5611_get_up; + baro->calculate = ms5611_calculate; + + return true; +} + +static void ms5611_reset(void) +{ + i2cWrite(MS5611_ADDR, CMD_RESET, 1); + delayMicroseconds(2800); +} + +static uint16_t ms5611_prom(int8_t coef_num) +{ + uint8_t rxbuf[2] = { 0, 0 }; + i2cRead(MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command + return rxbuf[0] << 8 | rxbuf[1]; +} + +static int8_t ms5611_crc(uint16_t *prom) +{ + int32_t i, j; + uint32_t res = 0; + uint8_t zero = 1; + uint8_t crc = prom[7] & 0xF; + prom[7] &= 0xFF00; + + // if eeprom is all zeros, we're probably fucked - BUT this will return valid CRC lol + for (i = 0; i < 8; i++) { + if (prom[i] != 0) + zero = 0; + } + if (zero) + return -1; + + for (i = 0; i < 16; i++) { + if (i & 1) + res ^= ((prom[i >> 1]) & 0x00FF); + else + res ^= (prom[i >> 1] >> 8); + for (j = 8; j > 0; j--) { + if (res & 0x8000) + res ^= 0x1800; + res <<= 1; + } + } + prom[7] |= crc; + if (crc == ((res >> 12) & 0xF)) + return 0; + + return -1; +} + +static uint32_t ms5611_read_adc(void) +{ + uint8_t rxbuf[3]; + i2cRead(MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC + return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2]; +} + +static void ms5611_start_ut(void) +{ + i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start! +} + +static void ms5611_get_ut(void) +{ + ms5611_ut = ms5611_read_adc(); +} + +static void ms5611_start_up(void) +{ + i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start! +} + +static void ms5611_get_up(void) +{ + ms5611_up = ms5611_read_adc(); +} + +static int32_t ms5611_calculate(void) +{ + int32_t temperature, off2 = 0, sens2 = 0, delt; + int32_t pressure; + + int32_t dT = ms5611_ut - ((uint32_t)ms5611_c[5] << 8); + int64_t off = ((uint32_t)ms5611_c[2] << 16) + (((int64_t)dT * ms5611_c[4]) >> 7); + int64_t sens = ((uint32_t)ms5611_c[1] << 15) + (((int64_t)dT * ms5611_c[3]) >> 8); + temperature = 2000 + (((int64_t)dT * ms5611_c[6]) >> 23); + + if (temperature < 2000) { // temperature lower than 20degC + delt = temperature - 2000; + delt = delt * delt; + off2 = (5 * delt) >> 1; + sens2 = (5 * delt) >> 2; + if (temperature < -1500) { // temperature lower than -15degC + delt = temperature + 1500; + delt = delt * delt; + off2 += 7 * delt; + sens2 += (11 * delt) >> 1; + } + } + off -= off2; + sens -= sens2; + pressure = (((ms5611_up * sens ) >> 21) - off) >> 15; + return pressure; +} diff --git a/src/baseflight/src/drv_ms5611.h b/src/baseflight/src/drv_ms5611.h new file mode 100644 index 0000000000..26cc371b85 --- /dev/null +++ b/src/baseflight/src/drv_ms5611.h @@ -0,0 +1,3 @@ +#pragma once + +bool ms5611Detect(baro_t *baro); diff --git a/src/baseflight/src/drv_pwm.c b/src/baseflight/src/drv_pwm.c new file mode 100755 index 0000000000..90c385c94b --- /dev/null +++ b/src/baseflight/src/drv_pwm.c @@ -0,0 +1,507 @@ +#include "board.h" + +#define PULSE_1MS (1000) // 1ms pulse width + +/* FreeFlight/Naze32 timer layout + TIM2_CH1 RC1 PWM1 + TIM2_CH2 RC2 PWM2 + TIM2_CH3 RC3/UA2_TX PWM3 + TIM2_CH4 RC4/UA2_RX PWM4 + TIM3_CH1 RC5 PWM5 + TIM3_CH2 RC6 PWM6 + TIM3_CH3 RC7 PWM7 + TIM3_CH4 RC8 PWM8 + TIM1_CH1 PWM1 PWM9 + TIM1_CH4 PWM2 PWM10 + TIM4_CH1 PWM3 PWM11 + TIM4_CH2 PWM4 PWM12 + TIM4_CH3 PWM5 PWM13 + TIM4_CH4 PWM6 PWM14 + + // RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration] + // RX2 TIM2_CH2 PA1 + // RX3 TIM2_CH3 PA2 [also UART2_TX] + // RX4 TIM2_CH4 PA3 [also UART2_RX] + // RX5 TIM3_CH1 PA6 [also ADC_IN6] + // RX6 TIM3_CH2 PA7 [also ADC_IN7] + // RX7 TIM3_CH3 PB0 [also ADC_IN8] + // RX8 TIM3_CH4 PB1 [also ADC_IN9] + + // Outputs + // PWM1 TIM1_CH1 PA8 + // PWM2 TIM1_CH4 PA11 + // PWM3 TIM4_CH1 PB6? [also I2C1_SCL] + // PWM4 TIM4_CH2 PB7 [also I2C1_SDA] + // PWM5 TIM4_CH3 PB8 + // PWM6 TIM4_CH4 PB9 + + Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc): + TIM2 4 channels + TIM3 4 channels + TIM1 2 channels + TIM4 4 channels + + Configuration maps: + + 1) multirotor PPM input + PWM1 used for PPM + PWM5..8 used for motors + PWM9..10 used for servo or else motors + PWM11..14 used for motors + + 2) multirotor PPM input with more servos + PWM1 used for PPM + PWM5..8 used for motors + PWM9..10 used for servo or else motors + PWM11..14 used for servos + + 2) multirotor PWM input + PWM1..8 used for input + PWM9..10 used for servo or else motors + PWM11..14 used for motors + + 3) airplane / flying wing w/PWM + PWM1..8 used for input + PWM9 used for motor throttle +PWM10 for 2nd motor + PWM11.14 used for servos + + 4) airplane / flying wing with PPM + PWM1 used for PPM + PWM5..8 used for servos + PWM9 used for motor throttle +PWM10 for 2nd motor + PWM11.14 used for servos +*/ + +typedef void pwmCallbackPtr(uint8_t port, uint16_t capture); + +static pwmHardware_t timerHardware[] = { + { TIM2, GPIOA, GPIO_Pin_0, TIM_Channel_1, TIM2_IRQn, 0, }, // PWM1 + { TIM2, GPIOA, GPIO_Pin_1, TIM_Channel_2, TIM2_IRQn, 0, }, // PWM2 + { TIM2, GPIOA, GPIO_Pin_2, TIM_Channel_3, TIM2_IRQn, 0, }, // PWM3 + { TIM2, GPIOA, GPIO_Pin_3, TIM_Channel_4, TIM2_IRQn, 0, }, // PWM4 + { TIM3, GPIOA, GPIO_Pin_6, TIM_Channel_1, TIM3_IRQn, 0, }, // PWM5 + { TIM3, GPIOA, GPIO_Pin_7, TIM_Channel_2, TIM3_IRQn, 0, }, // PWM6 + { TIM3, GPIOB, GPIO_Pin_0, TIM_Channel_3, TIM3_IRQn, 0, }, // PWM7 + { TIM3, GPIOB, GPIO_Pin_1, TIM_Channel_4, TIM3_IRQn, 0, }, // PWM8 + { TIM1, GPIOA, GPIO_Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, }, // PWM9 + { TIM1, GPIOA, GPIO_Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, }, // PWM10 + { TIM4, GPIOB, GPIO_Pin_6, TIM_Channel_1, TIM4_IRQn, 0, }, // PWM11 + { TIM4, GPIOB, GPIO_Pin_7, TIM_Channel_2, TIM4_IRQn, 0, }, // PWM12 + { TIM4, GPIOB, GPIO_Pin_8, TIM_Channel_3, TIM4_IRQn, 0, }, // PWM13 + { TIM4, GPIOB, GPIO_Pin_9, TIM_Channel_4, TIM4_IRQn, 0, }, // PWM14 +}; + +typedef struct { + pwmCallbackPtr *callback; + volatile uint16_t *ccr; + uint16_t period; + + // for input only + uint8_t channel; + uint8_t state; + uint16_t rise; + uint16_t fall; + uint16_t capture; +} pwmPortData_t; + +enum { + TYPE_IP = 0x10, + TYPE_IW = 0x20, + TYPE_M = 0x40, + TYPE_S = 0x80 +}; + +static pwmPortData_t pwmPorts[MAX_PORTS]; +static uint16_t captures[MAX_INPUTS]; +static pwmPortData_t *motors[MAX_MOTORS]; +static pwmPortData_t *servos[MAX_SERVOS]; +static uint8_t numMotors = 0; +static uint8_t numServos = 0; +static uint8_t numInputs = 0; +// external vars (ugh) +extern int16_t failsafeCnt; + +static const uint8_t multiPPM[] = { + PWM1 | TYPE_IP, // PPM input + PWM9 | TYPE_M, // Swap to servo if needed + PWM10 | TYPE_M, // Swap to servo if needed + PWM11 | TYPE_M, + PWM12 | TYPE_M, + PWM13 | TYPE_M, + PWM14 | TYPE_M, + PWM5 | TYPE_M, // Swap to servo if needed + PWM6 | TYPE_M, // Swap to servo if needed + PWM7 | TYPE_M, // Swap to servo if needed + PWM8 | TYPE_M, // Swap to servo if needed + 0xFF +}; + +static const uint8_t multiPWM[] = { + PWM1 | TYPE_IW, // input #1 + PWM2 | TYPE_IW, + PWM3 | TYPE_IW, + PWM4 | TYPE_IW, + PWM5 | TYPE_IW, + PWM6 | TYPE_IW, + PWM7 | TYPE_IW, + PWM8 | TYPE_IW, // input #8 + PWM9 | TYPE_M, // motor #1 or servo #1 (swap to servo if needed) + PWM10 | TYPE_M, // motor #2 or servo #2 (swap to servo if needed) + PWM11 | TYPE_M, // motor #1 or #3 + PWM12 | TYPE_M, + PWM13 | TYPE_M, + PWM14 | TYPE_M, // motor #4 or #6 + 0xFF +}; + +static const uint8_t airPPM[] = { + PWM1 | TYPE_IP, // PPM input + PWM9 | TYPE_M, // motor #1 + PWM10 | TYPE_M, // motor #2 + PWM11 | TYPE_S, // servo #1 + PWM12 | TYPE_S, + PWM13 | TYPE_S, + PWM14 | TYPE_S, // servo #4 + PWM5 | TYPE_S, // servo #5 + PWM6 | TYPE_S, + PWM7 | TYPE_S, + PWM8 | TYPE_S, // servo #8 + 0xFF +}; + +static const uint8_t airPWM[] = { + PWM1 | TYPE_IW, // input #1 + PWM2 | TYPE_IW, + PWM3 | TYPE_IW, + PWM4 | TYPE_IW, + PWM5 | TYPE_IW, + PWM6 | TYPE_IW, + PWM7 | TYPE_IW, + PWM8 | TYPE_IW, // input #8 + PWM9 | TYPE_M, // motor #1 + PWM10 | TYPE_M, // motor #2 + PWM11 | TYPE_S, // servo #1 + PWM12 | TYPE_S, + PWM13 | TYPE_S, + PWM14 | TYPE_S, // servo #4 + 0xFF +}; + +static const uint8_t *hardwareMaps[] = { + multiPWM, + multiPPM, + airPWM, + airPPM, +}; + +static void pwmTimeBase(TIM_TypeDef *tim, uint32_t period) +{ + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Period = period - 1; + TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 1000000) - 1; // all timers run at 1MHz + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure); +} + +static void pwmNVICConfig(uint8_t irq) +{ + NVIC_InitTypeDef NVIC_InitStructure; + + NVIC_InitStructure.NVIC_IRQChannel = irq; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +} + +static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value) +{ + TIM_OCInitTypeDef TIM_OCInitStructure; + + TIM_OCStructInit(&TIM_OCInitStructure); + TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStructure.TIM_Pulse = value; + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low; + TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; + + switch (channel) { + case TIM_Channel_1: + TIM_OC1Init(tim, &TIM_OCInitStructure); + TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_2: + TIM_OC2Init(tim, &TIM_OCInitStructure); + TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_3: + TIM_OC3Init(tim, &TIM_OCInitStructure); + TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_4: + TIM_OC4Init(tim, &TIM_OCInitStructure); + TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable); + break; + } +} + +static void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) +{ + TIM_ICInitTypeDef TIM_ICInitStructure; + + TIM_ICStructInit(&TIM_ICInitStructure); + TIM_ICInitStructure.TIM_Channel = channel; + TIM_ICInitStructure.TIM_ICPolarity = polarity; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0x0; + + TIM_ICInit(tim, &TIM_ICInitStructure); +} + +static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, uint8_t input) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = pin; + if (input) + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; + else + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_Init(gpio, &GPIO_InitStructure); +} + +static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value) +{ + pwmPortData_t *p = &pwmPorts[port]; + pwmTimeBase(timerHardware[port].tim, period); + pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, 0); + pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value); + // Needed only on TIM1 + if (timerHardware[port].outputEnable) + TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE); + TIM_Cmd(timerHardware[port].tim, ENABLE); + + switch (timerHardware[port].channel) { + case TIM_Channel_1: + p->ccr = &timerHardware[port].tim->CCR1; + break; + case TIM_Channel_2: + p->ccr = &timerHardware[port].tim->CCR2; + break; + case TIM_Channel_3: + p->ccr = &timerHardware[port].tim->CCR3; + break; + case TIM_Channel_4: + p->ccr = &timerHardware[port].tim->CCR4; + break; + } + return p; +} + +static pwmPortData_t *pwmInConfig(uint8_t port, pwmCallbackPtr callback, uint8_t channel) +{ + pwmPortData_t *p = &pwmPorts[port]; + pwmTimeBase(timerHardware[port].tim, 0xFFFF); + pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, 1); + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Rising); + TIM_Cmd(timerHardware[port].tim, ENABLE); + pwmNVICConfig(timerHardware[port].irq); + // set callback before configuring interrupts + p->callback = callback; + p->channel = channel; + + switch (timerHardware[port].channel) { + case TIM_Channel_1: + TIM_ITConfig(timerHardware[port].tim, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(timerHardware[port].tim, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(timerHardware[port].tim, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(timerHardware[port].tim, TIM_IT_CC4, ENABLE); + break; + } + return p; +} + +void TIM1_CC_IRQHandler(void) +{ + uint8_t port; + + if (TIM_GetITStatus(TIM1, TIM_IT_CC1) == SET) { + port = PWM9; + TIM_ClearITPendingBit(TIM1, TIM_IT_CC1); + pwmPorts[port].callback(port, TIM_GetCapture1(TIM1)); + } else if (TIM_GetITStatus(TIM1, TIM_IT_CC4) == SET) { + port = PWM10; + TIM_ClearITPendingBit(TIM1, TIM_IT_CC4); + pwmPorts[port].callback(port, TIM_GetCapture4(TIM1)); + } +} + +static void pwmTIMxHandler(TIM_TypeDef *tim, uint8_t portBase) +{ + int8_t port; + + // Generic CC handler for TIM2,3,4 + if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) { + port = portBase + 0; + TIM_ClearITPendingBit(tim, TIM_IT_CC1); + pwmPorts[port].callback(port, TIM_GetCapture1(tim)); + } else if (TIM_GetITStatus(tim, TIM_IT_CC2) == SET) { + port = portBase + 1; + TIM_ClearITPendingBit(tim, TIM_IT_CC2); + pwmPorts[port].callback(port, TIM_GetCapture2(tim)); + } else if (TIM_GetITStatus(tim, TIM_IT_CC3) == SET) { + port = portBase + 2; + TIM_ClearITPendingBit(tim, TIM_IT_CC3); + pwmPorts[port].callback(port, TIM_GetCapture3(tim)); + } else if (TIM_GetITStatus(tim, TIM_IT_CC4) == SET) { + port = portBase + 3; + TIM_ClearITPendingBit(tim, TIM_IT_CC4); + pwmPorts[port].callback(port, TIM_GetCapture4(tim)); + } +} + +void TIM2_IRQHandler(void) +{ + pwmTIMxHandler(TIM2, PWM1); // PWM1..4 +} + +void TIM3_IRQHandler(void) +{ + pwmTIMxHandler(TIM3, PWM5); // PWM5..8 +} + +void TIM4_IRQHandler(void) +{ + pwmTIMxHandler(TIM4, PWM11); // PWM11..14 +} + +static void ppmCallback(uint8_t port, uint16_t capture) +{ + uint16_t diff; + static uint16_t now; + static uint16_t last = 0; + static uint8_t chan = 0; + + last = now; + now = capture; + diff = now - last; + + if (diff > 2700) { // Per http://www.rcgroups.com/forums/showpost.php?p=21996147&postcount=3960 "So, if you use 2.5ms or higher as being the reset for the PPM stream start, you will be fine. I use 2.7ms just to be safe." + chan = 0; + } else { + if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range + captures[chan] = diff; + } + chan++; + failsafeCnt = 0; + } +} + +static void pwmCallback(uint8_t port, uint16_t capture) +{ + if (pwmPorts[port].state == 0) { + pwmPorts[port].rise = capture; + pwmPorts[port].state = 1; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Falling); + } else { + pwmPorts[port].fall = capture; + // compute capture + pwmPorts[port].capture = pwmPorts[port].fall - pwmPorts[port].rise; + captures[pwmPorts[port].channel] = pwmPorts[port].capture; + // switch state + pwmPorts[port].state = 0; + pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Rising); + // reset failsafe + failsafeCnt = 0; + } +} + +bool pwmInit(drv_pwm_config_t *init) +{ + int i = 0; + const uint8_t *setup; + + // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] + if (init->airplane) + i = 2; // switch to air hardware config + if (init->usePPM) + i++; // next index is for PPM + + setup = hardwareMaps[i]; + + for (i = 0; i < MAX_PORTS; i++) { + uint8_t port = setup[i] & 0x0F; + uint8_t mask = setup[i] & 0xF0; + + if (setup[i] == 0xFF) // terminator + break; + + // skip UART ports for GPS + if (init->useUART && (port == PWM3 || port == PWM4)) + continue; + + // skip ADC for powerMeter if configured + if (init->adcChannel && (init->adcChannel == port)) + continue; + + // hacks to allow current functionality + if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput) + mask = 0; + + if (init->useServos && !init->airplane) { + // remap PWM9+10 as servos (but not in airplane mode LOL) + if (port == PWM9 || port == PWM10) + mask = TYPE_S; + } + + if (init->extraServos && !init->airplane) { + // remap PWM5..8 as servos when used in extended servo mode + if (port >= PWM5 && port <= PWM8) + mask = TYPE_S; + } + + if (mask & TYPE_IP) { + pwmInConfig(port, ppmCallback, 0); + numInputs = 8; + } else if (mask & TYPE_IW) { + pwmInConfig(port, pwmCallback, numInputs); + numInputs++; + } else if (mask & TYPE_M) { + motors[numMotors++] = pwmOutConfig(port, 1000000 / init->motorPwmRate, PULSE_1MS); + } else if (mask & TYPE_S) { + servos[numServos++] = pwmOutConfig(port, 1000000 / init->servoPwmRate, PULSE_1MS); + } + } + + return false; +} + +void pwmWriteMotor(uint8_t index, uint16_t value) +{ + if (index < numMotors) + *motors[index]->ccr = value; +} + +void pwmWriteServo(uint8_t index, uint16_t value) +{ + if (index < numServos) + *servos[index]->ccr = value; +} + +uint16_t pwmRead(uint8_t channel) +{ + return captures[channel]; +} diff --git a/src/baseflight/src/drv_pwm.h b/src/baseflight/src/drv_pwm.h new file mode 100755 index 0000000000..9994e7f923 --- /dev/null +++ b/src/baseflight/src/drv_pwm.h @@ -0,0 +1,52 @@ +#pragma once + +#define MAX_MOTORS 12 +#define MAX_SERVOS 8 +#define MAX_INPUTS 8 + +typedef struct drv_pwm_config_t { + bool enableInput; + bool usePPM; + bool useUART; + bool useServos; + bool extraServos; // configure additional 4 channels in PPM mode as servos, not motors + bool airplane; // fixed wing hardware config, lots of servos etc + uint8_t adcChannel; // steal one RC input for current sensor + uint16_t motorPwmRate; + uint16_t servoPwmRate; +} drv_pwm_config_t; + +// This indexes into the read-only hardware definition structure in drv_pwm.c, as well as into pwmPorts[] structure with dynamic data. +enum { + PWM1 = 0, + PWM2, + PWM3, + PWM4, + PWM5, + PWM6, + PWM7, + PWM8, + PWM9, + PWM10, + PWM11, + PWM12, + PWM13, + PWM14, + MAX_PORTS +}; + +typedef struct { + TIM_TypeDef *tim; + GPIO_TypeDef *gpio; + uint32_t pin; + uint8_t channel; + uint8_t irq; + uint8_t outputEnable; +} pwmHardware_t; + +bool pwmInit(drv_pwm_config_t *init); // returns whether driver is asking to calibrate throttle or not +void pwmWriteMotor(uint8_t index, uint16_t value); +void pwmWriteServo(uint8_t index, uint16_t value); +uint16_t pwmRead(uint8_t channel); + +// void pwmWrite(uint8_t channel, uint16_t value); diff --git a/src/baseflight/src/drv_pwm_fy90q.c b/src/baseflight/src/drv_pwm_fy90q.c new file mode 100644 index 0000000000..165ee63651 --- /dev/null +++ b/src/baseflight/src/drv_pwm_fy90q.c @@ -0,0 +1,334 @@ +#ifdef FY90Q +#include "board.h" + +#define PULSE_1MS (1000) // 1ms pulse width +// #define PULSE_PERIOD (2500) // pulse period (400Hz) +// #define PULSE_PERIOD_SERVO_DIGITAL (5000) // pulse period for digital servo (200Hz) +// #define PULSE_PERIOD_SERVO_ANALOG (20000) // pulse period for analog servo (50Hz) + +// Forward declaration +static void pwmIRQHandler(TIM_TypeDef *tim); +static void ppmIRQHandler(TIM_TypeDef *tim); + +// external vars (ugh) +extern int16_t failsafeCnt; + +// local vars +static struct TIM_Channel { + TIM_TypeDef *tim; + uint16_t channel; + uint16_t cc; +} Channels[] = { + { TIM2, TIM_Channel_1, TIM_IT_CC1 }, + { TIM2, TIM_Channel_2, TIM_IT_CC2 }, + { TIM2, TIM_Channel_3, TIM_IT_CC3 }, + { TIM2, TIM_Channel_4, TIM_IT_CC4 }, + { TIM3, TIM_Channel_1, TIM_IT_CC1 }, + { TIM3, TIM_Channel_2, TIM_IT_CC2 }, + { TIM3, TIM_Channel_3, TIM_IT_CC3 }, + { TIM3, TIM_Channel_4, TIM_IT_CC4 }, +}; + +static volatile uint16_t *OutputChannels[] = { + &(TIM4->CCR1), + &(TIM4->CCR2), + &(TIM4->CCR3), + &(TIM4->CCR4), + // Extended use during CPPM input (TODO) + &(TIM3->CCR1), + &(TIM3->CCR2), + &(TIM3->CCR3), + &(TIM3->CCR4), +}; + +static struct PWM_State { + uint8_t state; + uint16_t rise; + uint16_t fall; + uint16_t capture; +} Inputs[8] = { { 0, } }; + +static TIM_ICInitTypeDef TIM_ICInitStructure = { 0, }; +static bool usePPMFlag = false; +static uint8_t numOutputChannels = 0; + +void TIM2_IRQHandler(void) +{ + if (usePPMFlag) + ppmIRQHandler(TIM2); + else + pwmIRQHandler(TIM2); +} + +static void ppmIRQHandler(TIM_TypeDef *tim) +{ + uint16_t diff; + static uint16_t now; + static uint16_t last = 0; + static uint8_t chan = 0; + + if (TIM_GetITStatus(tim, TIM_IT_CC1) == SET) { + last = now; + now = TIM_GetCapture1(tim); + rcActive = true; + } + + TIM_ClearITPendingBit(tim, TIM_IT_CC1); + + if (now > last) { + diff = (now - last); + } else { + diff = ((0xFFFF - last) + now); + } + + if (diff > 4000) { + chan = 0; + } else { + if (diff > 750 && diff < 2250 && chan < 8) { // 750 to 2250 ms is our 'valid' channel range + Inputs[chan].capture = diff; + } + chan++; + failsafeCnt = 0; + } +} + +static void pwmIRQHandler(TIM_TypeDef *tim) +{ + uint8_t i; + uint16_t val = 0; + + for (i = 0; i < 8; i++) { + struct TIM_Channel channel = Channels[i]; + struct PWM_State *state = &Inputs[i]; + + if (channel.tim == tim && (TIM_GetITStatus(tim, channel.cc) == SET)) { + TIM_ClearITPendingBit(channel.tim, channel.cc); + + switch (channel.channel) { + case TIM_Channel_1: + val = TIM_GetCapture1(channel.tim); + break; + case TIM_Channel_2: + val = TIM_GetCapture2(channel.tim); + break; + case TIM_Channel_3: + val = TIM_GetCapture3(channel.tim); + break; + case TIM_Channel_4: + val = TIM_GetCapture4(channel.tim); + break; + } + + if (state->state == 0) + state->rise = val; + else + state->fall = val; + + if (state->state == 0) { + // switch states + state->state = 1; + + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.tim, &TIM_ICInitStructure); + } else { + // compute capture + if (state->fall > state->rise) + state->capture = (state->fall - state->rise); + else + state->capture = ((0xffff - state->rise) + state->fall); + + // switch state + state->state = 0; + + // ping failsafe + failsafeCnt = 0; + + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.tim, &TIM_ICInitStructure); + } + } + } +} + +static void pwmInitializeInput(bool usePPM) +{ + GPIO_InitTypeDef GPIO_InitStructure = { 0, }; + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, }; + NVIC_InitTypeDef NVIC_InitStructure = { 0, }; + uint8_t i; + + // Input pins + if (usePPM) { + // Configure TIM2_CH1 for PPM input + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + // Input timer on TIM2 only for PPM + NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + // TIM2 timebase + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1); + TIM_TimeBaseStructure.TIM_Period = 0xffff; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + + // Input capture on TIM2_CH1 for PPM + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0x0; + TIM_ICInitStructure.TIM_Channel = TIM_Channel_1; + TIM_ICInit(TIM2, &TIM_ICInitStructure); + + // TIM2_CH1 capture compare interrupt enable + TIM_ITConfig(TIM2, TIM_IT_CC1, ENABLE); + TIM_Cmd(TIM2, ENABLE); + + // configure number of PWM outputs, in PPM mode, we use bottom 4 channels more more motors + numOutputChannels = 10; + } else { + // Configure TIM2 all 4 channels + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 | GPIO_Pin_3 | GPIO_Pin_4; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + // TODO Configure EXTI4 1 channel + + // Input timers on TIM2 for PWM + NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + // TIM2 timebase + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1); + TIM_TimeBaseStructure.TIM_Period = 0xffff; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + + // PWM Input capture + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI; + TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; + TIM_ICInitStructure.TIM_ICFilter = 0x0; + + for (i = 0; i < 4; i++) { + TIM_ICInitStructure.TIM_Channel = Channels[i].channel; + TIM_ICInit(Channels[i].tim, &TIM_ICInitStructure); + } + + // TODO EXTI4 + + TIM_ITConfig(TIM2, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, ENABLE); + // TODO EXTI4 + TIM_Cmd(TIM2, ENABLE); + + // In PWM input mode, all 4 channels are wasted + numOutputChannels = 4; + } +} + +bool pwmInit(drv_pwm_config_t *init) +{ + GPIO_InitTypeDef GPIO_InitStructure = { 0, }; + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = { 0, }; + TIM_OCInitTypeDef TIM_OCInitStructure = { 0, }; + + uint8_t i; + + // Inputs + + // RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration] + // RX2 TIM2_CH2 PA1 + // RX3 TIM2_CH3 PA2 [also UART2_TX] + // RX4 TIM2_CH4 PA3 [also UART2_RX] + // RX5 TIM3_CH1 PA6 [also ADC_IN6] + // RX6 TIM3_CH2 PA7 [also ADC_IN7] + // RX7 TIM3_CH3 PB0 [also ADC_IN8] + // RX8 TIM3_CH4 PB1 [also ADC_IN9] + + // Outputs + // PWM1 TIM1_CH1 PA8 + // PWM2 TIM1_CH4 PA11 + // PWM3 TIM4_CH1 PB6 [also I2C1_SCL] + // PWM4 TIM4_CH2 PB7 [also I2C1_SDA] + // PWM5 TIM4_CH3 PB8 + // PWM6 TIM4_CH4 PB9 + + // use PPM or PWM input + usePPMFlag = init->usePPM; + + // preset channels to center + for (i = 0; i < 8; i++) + Inputs[i].capture = 1500; + + // Timers run at 1mhz. + // TODO: clean this shit up. Make it all dynamic etc. + if (init->enableInput) + pwmInitializeInput(usePPMFlag); + + // Output pins (4x) + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 | GPIO_Pin_9; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + // Output timer + TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); + TIM_TimeBaseStructure.TIM_Prescaler = (72 - 1); + + TIM_TimeBaseStructure.TIM_Period = (1000000 / init->motorPwmRate) - 1; + TIM_TimeBaseInit(TIM4, &TIM_TimeBaseStructure); + + TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2; + TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; + TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; + TIM_OCInitStructure.TIM_Pulse = PULSE_1MS; + TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_Low; + TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; + + // PWM1,2,3,4 + TIM_OC1Init(TIM4, &TIM_OCInitStructure); + TIM_OC2Init(TIM4, &TIM_OCInitStructure); + TIM_OC3Init(TIM4, &TIM_OCInitStructure); + TIM_OC4Init(TIM4, &TIM_OCInitStructure); + TIM_OC1PreloadConfig(TIM4, TIM_OCPreload_Enable); + TIM_OC2PreloadConfig(TIM4, TIM_OCPreload_Enable); + TIM_OC3PreloadConfig(TIM4, TIM_OCPreload_Enable); + TIM_OC4PreloadConfig(TIM4, TIM_OCPreload_Enable); + + TIM_Cmd(TIM4, ENABLE); + TIM_CtrlPWMOutputs(TIM4, ENABLE); + TIM_OC1PreloadConfig (TIM4, TIM_OCPreload_Enable); + + // turn on more motor outputs if we're using ppm / not using pwm input + if (!init->enableInput || init->usePPM) { + // TODO + } + + return false; +} + +void pwmWrite(uint8_t channel, uint16_t value) +{ + if (channel < numOutputChannels) + *OutputChannels[channel] = value; +} + +uint16_t pwmRead(uint8_t channel) +{ + return Inputs[channel].capture; +} +#endif diff --git a/src/baseflight/src/drv_system.c b/src/baseflight/src/drv_system.c new file mode 100755 index 0000000000..4a6b2000fb --- /dev/null +++ b/src/baseflight/src/drv_system.c @@ -0,0 +1,171 @@ +#include "board.h" + +typedef struct gpio_config_t +{ + GPIO_TypeDef *gpio; + uint16_t pin; + GPIOMode_TypeDef mode; +} gpio_config_t; + +// cycles per microsecond +static volatile uint32_t usTicks = 0; +// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care. +static volatile uint32_t sysTickUptime = 0; + +static void cycleCounterInit(void) +{ + RCC_ClocksTypeDef clocks; + RCC_GetClocksFreq(&clocks); + usTicks = clocks.SYSCLK_Frequency / 1000000; +} + +// SysTick +void SysTick_Handler(void) +{ + sysTickUptime++; +} + +// Return system uptime in microseconds (rollover in 70minutes) +uint32_t micros(void) +{ + register uint32_t ms, cycle_cnt; + do { + ms = sysTickUptime; + cycle_cnt = SysTick->VAL; + } while (ms != sysTickUptime); + return (ms * 1000) + (72000 - cycle_cnt) / 72; +} + +// Return system uptime in milliseconds (rollover in 49 days) +uint32_t millis(void) +{ + return sysTickUptime; +} + +void systemInit(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + uint32_t i; + + gpio_config_t gpio_cfg[] = { + { LED0_GPIO, LED0_PIN, GPIO_Mode_Out_PP }, // PB3 (LED) + { LED1_GPIO, LED1_PIN, GPIO_Mode_Out_PP }, // PB4 (LED) +#ifndef FY90Q + { BEEP_GPIO, BEEP_PIN, GPIO_Mode_Out_OD }, // PA12 (Buzzer) +#endif + }; + uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]); + + // This is needed because some shit inside Keil startup fucks with SystemCoreClock, setting it back to 72MHz even on HSI. + SystemCoreClockUpdate(); + + // Turn on clocks for stuff we use + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_I2C2, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC | RCC_APB2Periph_TIM1 | RCC_APB2Periph_ADC1 | RCC_APB2Periph_USART1, ENABLE); + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClearFlag(); + + // Make all GPIO in by default to save power and reduce noise + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN; + GPIO_Init(GPIOA, &GPIO_InitStructure); + GPIO_Init(GPIOB, &GPIO_InitStructure); + GPIO_Init(GPIOC, &GPIO_InitStructure); + + // Turn off JTAG port 'cause we're using the GPIO for leds + GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE); + + // Configure gpio + for (i = 0; i < gpio_count; i++) { + GPIO_InitStructure.GPIO_Pin = gpio_cfg[i].pin; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = gpio_cfg[i].mode; + GPIO_Init(gpio_cfg[i].gpio, &GPIO_InitStructure); + } + + LED0_OFF; + LED1_OFF; + BEEP_OFF; + + // Init cycle counter + cycleCounterInit(); + + // SysTick + SysTick_Config(SystemCoreClock / 1000); + + // Configure the rest of the stuff +#ifndef FY90Q + i2cInit(I2C2); +#endif + + // sleep for 100ms + delay(100); +} + +#if 1 +void delayMicroseconds(uint32_t us) +{ + uint32_t now = micros(); + while (micros() - now < us); +} +#else +void delayMicroseconds(uint32_t us) +{ + uint32_t elapsed = 0; + uint32_t lastCount = SysTick->VAL; + + for (;;) { + register uint32_t current_count = SysTick->VAL; + uint32_t elapsed_us; + + // measure the time elapsed since the last time we checked + elapsed += current_count - lastCount; + lastCount = current_count; + + // convert to microseconds + elapsed_us = elapsed / usTicks; + if (elapsed_us >= us) + break; + + // reduce the delay by the elapsed time + us -= elapsed_us; + + // keep fractional microseconds for the next iteration + elapsed %= usTicks; + } +} +#endif + +void delay(uint32_t ms) +{ + while (ms--) + delayMicroseconds(1000); +} + +void failureMode(uint8_t mode) +{ + LED1_ON; + LED0_OFF; + while (1) { + LED1_TOGGLE; + LED0_TOGGLE; + delay(475 * mode - 2); + BEEP_ON + delay(25); + BEEP_OFF; + } +} + +#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000) + +void systemReset(bool toBootloader) +{ + if (toBootloader) { + // 1FFFF000 -> 20000200 -> SP + // 1FFFF004 -> 1FFFF021 -> PC + *((uint32_t *)0x20004FF0) = 0xDEADBEEF; // 20KB STM32F103 + } + + // Generate system reset + SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; +} diff --git a/src/baseflight/src/drv_system.h b/src/baseflight/src/drv_system.h new file mode 100755 index 0000000000..baf361b2fb --- /dev/null +++ b/src/baseflight/src/drv_system.h @@ -0,0 +1,14 @@ +#pragma once + +void systemInit(void); +void delayMicroseconds(uint32_t us); +void delay(uint32_t ms); + +uint32_t micros(void); +uint32_t millis(void); + +// failure +void failureMode(uint8_t mode); + +// bootloader/IAP +void systemReset(bool toBootloader); diff --git a/src/baseflight/src/drv_uart.c b/src/baseflight/src/drv_uart.c new file mode 100755 index 0000000000..978fdb642f --- /dev/null +++ b/src/baseflight/src/drv_uart.c @@ -0,0 +1,245 @@ +#include "board.h" + +/* + DMA UART routines idea lifted from AutoQuad + Copyright © 2011 Bill Nesbitt +*/ +#define UART_BUFFER_SIZE 256 + +// Receive buffer, circular DMA +volatile uint8_t rxBuffer[UART_BUFFER_SIZE]; +uint32_t rxDMAPos = 0; +volatile uint8_t txBuffer[UART_BUFFER_SIZE]; +uint32_t txBufferTail = 0; +uint32_t txBufferHead = 0; + +static void uartTxDMA(void) +{ + DMA1_Channel4->CMAR = (uint32_t)&txBuffer[txBufferTail]; + if (txBufferHead > txBufferTail) { + DMA1_Channel4->CNDTR = txBufferHead - txBufferTail; + txBufferTail = txBufferHead; + } else { + DMA1_Channel4->CNDTR = UART_BUFFER_SIZE - txBufferTail; + txBufferTail = 0; + } + + DMA_Cmd(DMA1_Channel4, ENABLE); +} + +void DMA1_Channel4_IRQHandler(void) +{ + DMA_ClearITPendingBit(DMA1_IT_TC4); + DMA_Cmd(DMA1_Channel4, DISABLE); + + if (txBufferHead != txBufferTail) + uartTxDMA(); +} + +void uartInit(uint32_t speed) +{ + GPIO_InitTypeDef GPIO_InitStructure; + USART_InitTypeDef USART_InitStructure; + DMA_InitTypeDef DMA_InitStructure; + NVIC_InitTypeDef NVIC_InitStructure; + + // USART1_TX PA9 + // USART1_RX PA10 + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(GPIOA, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + // DMA TX Interrupt + NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + USART_InitStructure.USART_BaudRate = speed; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_Init(USART1, &USART_InitStructure); + + // Receive DMA into a circular buffer + DMA_DeInit(DMA1_Channel5); + DMA_InitStructure.DMA_Priority = DMA_Priority_Medium; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR; + DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)rxBuffer; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + DMA_InitStructure.DMA_BufferSize = UART_BUFFER_SIZE; + DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; + DMA_Init(DMA1_Channel5, &DMA_InitStructure); + + DMA_Cmd(DMA1_Channel5, ENABLE); + USART_DMACmd(USART1, USART_DMAReq_Rx, ENABLE); + rxDMAPos = DMA_GetCurrDataCounter(DMA1_Channel5); + + // Transmit DMA + DMA_DeInit(DMA1_Channel4); + DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USART1->DR; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; + DMA_Init(DMA1_Channel4, &DMA_InitStructure); + DMA_ITConfig(DMA1_Channel4, DMA_IT_TC, ENABLE); + DMA1_Channel4->CNDTR = 0; + USART_DMACmd(USART1, USART_DMAReq_Tx, ENABLE); + + USART_Cmd(USART1, ENABLE); +} + +uint16_t uartAvailable(void) +{ + return (DMA_GetCurrDataCounter(DMA1_Channel5) != rxDMAPos) ? true : false; +} + +bool uartTransmitEmpty(void) +{ + return (txBufferTail == txBufferHead); +} + +uint8_t uartRead(void) +{ + uint8_t ch; + + ch = rxBuffer[UART_BUFFER_SIZE - rxDMAPos]; + // go back around the buffer + if (--rxDMAPos == 0) + rxDMAPos = UART_BUFFER_SIZE; + + return ch; +} + +uint8_t uartReadPoll(void) +{ + while (!uartAvailable()); // wait for some bytes + return uartRead(); +} + +void uartWrite(uint8_t ch) +{ + txBuffer[txBufferHead] = ch; + txBufferHead = (txBufferHead + 1) % UART_BUFFER_SIZE; + + // if DMA wasn't enabled, fire it up + if (!(DMA1_Channel4->CCR & 1)) + uartTxDMA(); +} + +void uartPrint(char *str) +{ + while (*str) + uartWrite(*(str++)); +} + +/* -------------------------- UART2 (Spektrum, GPS) ----------------------------- */ +uartReceiveCallbackPtr uart2Callback = NULL; +#define UART2_BUFFER_SIZE 128 + +volatile uint8_t tx2Buffer[UART2_BUFFER_SIZE]; +uint32_t tx2BufferTail = 0; +uint32_t tx2BufferHead = 0; +bool uart2RxOnly = false; + +static void uart2Open(uint32_t speed) +{ + USART_InitTypeDef USART_InitStructure; + + USART_StructInit(&USART_InitStructure); + USART_InitStructure.USART_BaudRate = speed; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_Mode = USART_Mode_Rx | (uart2RxOnly ? 0 : USART_Mode_Tx); + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_Init(USART2, &USART_InitStructure); + USART_Cmd(USART2, ENABLE); +} + +void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly) +{ + NVIC_InitTypeDef NVIC_InitStructure; + GPIO_InitTypeDef GPIO_InitStructure; + + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + + uart2RxOnly = rxOnly; + + NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 2; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + // USART2_TX PA2 + // USART2_RX PA3 + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + if (!rxOnly) + GPIO_Init(GPIOA, &GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + uart2Open(speed); + USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); + if (!rxOnly) + USART_ITConfig(USART2, USART_IT_TXE, ENABLE); + uart2Callback = func; +} + +void uart2ChangeBaud(uint32_t speed) +{ + uart2Open(speed); +} + +void uart2Write(uint8_t ch) +{ + if (uart2RxOnly) + return; + + tx2Buffer[tx2BufferHead] = ch; + tx2BufferHead = (tx2BufferHead + 1) % UART2_BUFFER_SIZE; + + USART_ITConfig(USART2, USART_IT_TXE, ENABLE); +} + +bool uart2TransmitEmpty(void) +{ + return tx2BufferTail == tx2BufferHead; +} + +void USART2_IRQHandler(void) +{ + uint16_t SR = USART2->SR; + + if (SR & USART_IT_RXNE) { + if (uart2Callback) + uart2Callback(USART_ReceiveData(USART2)); + } + if (SR & USART_FLAG_TXE) { + if (tx2BufferTail != tx2BufferHead) { + USART2->DR = tx2Buffer[tx2BufferTail]; + tx2BufferTail = (tx2BufferTail + 1) % UART2_BUFFER_SIZE; + } else { + USART_ITConfig(USART2, USART_IT_TXE, DISABLE); + } + } +} diff --git a/src/baseflight/src/drv_uart.h b/src/baseflight/src/drv_uart.h new file mode 100755 index 0000000000..f029b0ec2d --- /dev/null +++ b/src/baseflight/src/drv_uart.h @@ -0,0 +1,16 @@ +#pragma once + +// USART1 +void uartInit(uint32_t speed); +uint16_t uartAvailable(void); +bool uartTransmitEmpty(void); +uint8_t uartRead(void); +uint8_t uartReadPoll(void); +void uartWrite(uint8_t ch); +void uartPrint(char *str); + +// USART2 (GPS, Spektrum) +void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly); +void uart2ChangeBaud(uint32_t speed); +bool uart2TransmitEmpty(void); +void uart2Write(uint8_t ch); diff --git a/src/baseflight/src/gps.c b/src/baseflight/src/gps.c new file mode 100644 index 0000000000..c6aaa320a1 --- /dev/null +++ b/src/baseflight/src/gps.c @@ -0,0 +1,1087 @@ +#include "board.h" +#include "mw.h" + +#ifndef sq +#define sq(x) ((x)*(x)) +#endif + +const uint32_t init_speed[5] = { 9600, 19200, 38400, 57600, 115200 }; + +static void GPS_NewData(uint16_t c); +static void GPS_set_pids(void); +static void gpsPrint(const char *str); + +static const char * const gpsInitStrings[] = { + "$PUBX,41,1,0003,0001,19200,0*23\r\n", // UBX0..3 + "$PUBX,41,1,0003,0001,38400,0*26\r\n", + "$PUBX,41,1,0003,0001,57600,0*2D\r\n", + "$PUBX,41,1,0003,0001,115200,0*1E\r\n", + "$PMTK251,19200*22\r\n", // MTK4..7 + "$PMTK251,38400*27\r\n", + "$PMTK251,57600*2C\r\n", + "$PMTK251,115200*1F\r\n", +}; + +static const uint8_t ubloxInit[] = { + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x05, 0x00, 0xFF, 0x19, // disable all default NMEA messages + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x03, 0x00, 0xFD, 0x15, + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x01, 0x00, 0xFB, 0x11, + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x00, 0x00, 0xFA, 0x0F, + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x02, 0x00, 0xFC, 0x13, + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0xF0, 0x04, 0x00, 0xFE, 0x17, + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x02, 0x01, 0x0E, 0x47, // set POSLLH MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x03, 0x01, 0x0F, 0x49, // set STATUS MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x06, 0x01, 0x12, 0x4F, // set SOL MSG rate + 0xB5, 0x62, 0x06, 0x01, 0x03, 0x00, 0x01, 0x12, 0x01, 0x1E, 0x67, // set VELNED MSG rate + 0xB5, 0x62, 0x06, 0x16, 0x08, 0x00, 0x03, 0x07, 0x03, 0x00, 0x51, 0x08, 0x00, 0x00, 0x8A, 0x41, // set WAAS to EGNOS + 0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A // set rate to 5Hz +}; + +void gpsInit(uint32_t baudrate) +{ + int i; + int offset = 0; + + GPS_set_pids(); + uart2Init(baudrate, GPS_NewData, false); + + if (cfg.gps_type == GPS_UBLOX) + offset = 0; + else if (cfg.gps_type == GPS_MTK) + offset = 4; + + if (cfg.gps_type != GPS_NMEA) { + for (i = 0; i < 5; i++) { + uart2ChangeBaud(init_speed[i]); + switch (baudrate) { + case 19200: + gpsPrint(gpsInitStrings[offset]); + break; + case 38400: + gpsPrint(gpsInitStrings[offset + 1]); + break; + case 57600: + gpsPrint(gpsInitStrings[offset + 2]); + break; + case 115200: + gpsPrint(gpsInitStrings[offset + 3]); + break; + } + delay(10); + } + } + + uart2ChangeBaud(baudrate); + if (cfg.gps_type == GPS_UBLOX) { + for (i = 0; i < sizeof(ubloxInit); i++) { + uart2Write(ubloxInit[i]); // send ubx init binary + delay(4); + } + } else if (cfg.gps_type == GPS_MTK) { + gpsPrint("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n"); // only GGA and RMC sentence + gpsPrint("$PMTK220,200*2C\r\n"); // 5 Hz update rate + } + + // catch some GPS frames. TODO check this + delay(1000); + if (GPS_Present) + sensorsSet(SENSOR_GPS); +} + +static void gpsPrint(const char *str) +{ + while (*str) { + uart2Write(*str); + if (cfg.gps_type == GPS_UBLOX) + delay(4); + str++; + } + // wait to send all + while (!uart2TransmitEmpty()); + delay(30); +} + +/*----------------------------------------------------------- + * + * Multiwii GPS code - revision: 1097 + * + *-----------------------------------------------------------*/ +#define POSHOLD_IMAX 20 // degrees +#define POSHOLD_RATE_IMAX 20 // degrees +#define NAV_IMAX 20 // degrees + +/* GPS navigation can control the heading */ +#define NAV_TAIL_FIRST 0 // true - copter comes in with tail first +#define NAV_SET_TAKEOFF_HEADING 1 // true - when copter arrives to home position it rotates it's head to takeoff direction + +#define GPS_FILTERING 1 // add a 5 element moving average filter to GPS coordinates, helps eliminate gps noise but adds latency +#define GPS_LOW_SPEED_D_FILTER 1 // below .5m/s speed ignore D term for POSHOLD_RATE, theoretically this also removed D term induced noise + +static bool check_missed_wp(void); +static void GPS_distance_cm_bearing(int32_t * lat1, int32_t * lon1, int32_t * lat2, int32_t * lon2, uint32_t * dist, int32_t * bearing); +//static void GPS_distance(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2, uint16_t* dist, int16_t* bearing); +static void GPS_calc_longitude_scaling(int32_t lat); +static void GPS_calc_velocity(void); +static void GPS_calc_location_error(int32_t * target_lat, int32_t * target_lng, int32_t * gps_lat, int32_t * gps_lng); +static void GPS_calc_poshold(void); +static void GPS_calc_nav_rate(int max_speed); +static void GPS_update_crosstrack(void); +static bool GPS_newFrame(char c); +static bool GPS_NMEA_newFrame(char c); +static bool GPS_UBLOX_newFrame(uint8_t data); +static bool UBLOX_parse_gps(void); +static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow); +int32_t wrap_18000(int32_t error); +static int32_t wrap_36000(int32_t angle); + +typedef struct { + float kP; + float kI; + float kD; + float Imax; +} PID_PARAM; + +static PID_PARAM posholdPID_PARAM; +static PID_PARAM poshold_ratePID_PARAM; +static PID_PARAM navPID_PARAM; + +typedef struct { + float integrator; // integrator value + int32_t last_input; // last input for derivative + float last_derivative; // last derivative for low-pass filter + float output; + float derivative; +} PID; + +static PID posholdPID[2]; +static PID poshold_ratePID[2]; +static PID navPID[2]; + +static int32_t get_P(int32_t error, PID_PARAM *pid) +{ + return (float)error * pid->kP; +} + +static int32_t get_I(int32_t error, float *dt, PID *pid, PID_PARAM *pid_param) +{ + pid->integrator += ((float)error * pid_param->kI) * *dt; + pid->integrator = constrain(pid->integrator, -pid_param->Imax, pid_param->Imax); + return pid->integrator; +} + +static int32_t get_D(int32_t input, float *dt, PID *pid, PID_PARAM *pid_param) +{ + pid->derivative = (input - pid->last_input) / *dt; + + // Low pass filter cut frequency for derivative calculation + // Set to "1 / ( 2 * PI * gps_lpf )" +#define PID_FILTER (1.0f / (2.0f * M_PI * (float)cfg.gps_lpf)) + // discrete low pass filter, cuts out the + // high frequency noise that can drive the controller crazy + pid->derivative = pid->last_derivative + (*dt / (PID_FILTER + *dt)) * (pid->derivative - pid->last_derivative); + // update state + pid->last_input = input; + pid->last_derivative = pid->derivative; + // add in derivative component + return pid_param->kD * pid->derivative; +} + +static void reset_PID(PID *pid) +{ + pid->integrator = 0; + pid->last_input = 0; + pid->last_derivative = 0; +} + +#define GPS_X 1 +#define GPS_Y 0 + +/****************** PI and PID controllers for GPS ********************///32938 -> 33160 + +#define RADX100 0.000174532925f +#define CROSSTRACK_GAIN 1 +#define NAV_SLOW_NAV true +#define NAV_BANK_MAX 3000 // 30deg max banking when navigating (just for security and testing) + +static float dTnav; // Delta Time in milliseconds for navigation computations, updated with every good GPS read +static int16_t actual_speed[2] = { 0, 0 }; +static float GPS_scaleLonDown; // this is used to offset the shrinking longitude as we go towards the poles + +// The difference between the desired rate of travel and the actual rate of travel +// updated after GPS read - 5-10hz +static int16_t rate_error[2]; +static int32_t error[2]; + +// Currently used WP +static int32_t GPS_WP[2]; + +//////////////////////////////////////////////////////////////////////////////// +// Location & Navigation +//////////////////////////////////////////////////////////////////////////////// +// This is the angle from the copter to the "next_WP" location in degrees * 100 +static int32_t target_bearing; +//////////////////////////////////////////////////////////////////////////////// +// Crosstrack +//////////////////////////////////////////////////////////////////////////////// +// deg * 100, The original angle to the next_WP when the next_WP was set +// Also used to check when we pass a WP +static int32_t original_target_bearing; +// The amount of angle correction applied to target_bearing to bring the copter back on its optimum path +static int16_t crosstrack_error; +//////////////////////////////////////////////////////////////////////////////// +// The location of the copter in relation to home, updated every GPS read (1deg - 100) +//static int32_t home_to_copter_bearing; +// distance between plane and home in cm +//static int32_t home_distance; +// distance between plane and next_WP in cm +static uint32_t wp_distance; + +// used for slow speed wind up when start navigation; +static int16_t waypoint_speed_gov; + +//////////////////////////////////////////////////////////////////////////////////// +// moving average filter variables +// +#define GPS_FILTER_VECTOR_LENGTH 5 + +static uint8_t GPS_filter_index = 0; +static int32_t GPS_filter[2][GPS_FILTER_VECTOR_LENGTH]; +static int32_t GPS_filter_sum[2]; +static int32_t GPS_read[2]; +static int32_t GPS_filtered[2]; +static int32_t GPS_degree[2]; //the lat lon degree without any decimals (lat/10 000 000) +static uint16_t fraction3[2]; + +// This is the angle from the copter to the "next_WP" location +// with the addition of Crosstrack error in degrees * 100 +static int32_t nav_bearing; +// saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home +static int16_t nav_takeoff_bearing; + +void GPS_NewData(uint16_t c) +{ + int axis; + static uint32_t nav_loopTimer; + uint32_t dist; + int32_t dir; + int16_t speed; + + if (GPS_newFrame(c)) { + if (GPS_update == 1) + GPS_update = 0; + else + GPS_update = 1; + if (f.GPS_FIX && GPS_numSat >= 5) { + if (!f.ARMED) + f.GPS_FIX_HOME = 0; + if (!f.GPS_FIX_HOME && f.ARMED) + GPS_reset_home_position(); + // Apply moving average filter to GPS data +#if defined(GPS_FILTERING) + GPS_filter_index = (GPS_filter_index + 1) % GPS_FILTER_VECTOR_LENGTH; + for (axis = 0; axis < 2; axis++) { + GPS_read[axis] = GPS_coord[axis]; // latest unfiltered data is in GPS_latitude and GPS_longitude + GPS_degree[axis] = GPS_read[axis] / 10000000; // get the degree to assure the sum fits to the int32_t + + // How close we are to a degree line ? its the first three digits from the fractions of degree + // later we use it to Check if we are close to a degree line, if yes, disable averaging, + fraction3[axis] = (GPS_read[axis] - GPS_degree[axis] * 10000000) / 10000; + + GPS_filter_sum[axis] -= GPS_filter[axis][GPS_filter_index]; + GPS_filter[axis][GPS_filter_index] = GPS_read[axis] - (GPS_degree[axis] * 10000000); + GPS_filter_sum[axis] += GPS_filter[axis][GPS_filter_index]; + GPS_filtered[axis] = GPS_filter_sum[axis] / GPS_FILTER_VECTOR_LENGTH + (GPS_degree[axis] * 10000000); + if (nav_mode == NAV_MODE_POSHOLD) { // we use gps averaging only in poshold mode... + if (fraction3[axis] > 1 && fraction3[axis] < 999) + GPS_coord[axis] = GPS_filtered[axis]; + } + } +#endif + // dTnav calculation + // Time for calculating x,y speed and navigation pids + dTnav = (float) (millis() - nav_loopTimer) / 1000.0f; + nav_loopTimer = millis(); + // prevent runup from bad GPS + dTnav = min(dTnav, 1.0f); + + // calculate distance and bearings for gui and other stuff continously - From home to copter + GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_home[LAT], &GPS_home[LON], &dist, &dir); + GPS_distanceToHome = dist / 100; + GPS_directionToHome = dir / 100; + + if (!f.GPS_FIX_HOME) { // If we don't have home set, do not display anything + GPS_distanceToHome = 0; + GPS_directionToHome = 0; + } + + // calculate the current velocity based on gps coordinates continously to get a valid speed at the moment when we start navigating + GPS_calc_velocity(); + + if (f.GPS_HOLD_MODE || f.GPS_HOME_MODE) { // ok we are navigating + // do gps nav calculations here, these are common for nav and poshold + GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_WP[LAT], &GPS_WP[LON], &wp_distance, &target_bearing); + GPS_calc_location_error(&GPS_WP[LAT], &GPS_WP[LON], &GPS_coord[LAT], &GPS_coord[LON]); + + switch (nav_mode) { + case NAV_MODE_POSHOLD: + // Desired output is in nav_lat and nav_lon where 1deg inclination is 100 + GPS_calc_poshold(); + break; + + case NAV_MODE_WP: + speed = GPS_calc_desired_speed(cfg.nav_speed_max, NAV_SLOW_NAV); // slow navigation + // use error as the desired rate towards the target + // Desired output is in nav_lat and nav_lon where 1deg inclination is 100 + GPS_calc_nav_rate(speed); + + // Tail control + if (cfg.nav_controls_heading) { + if (NAV_TAIL_FIRST) { + magHold = wrap_18000(nav_bearing - 18000) / 100; + } else { + magHold = nav_bearing / 100; + } + } + // Are we there yet ?(within x meters of the destination) + if ((wp_distance <= cfg.gps_wp_radius) || check_missed_wp()) { // if yes switch to poshold mode + nav_mode = NAV_MODE_POSHOLD; + if (NAV_SET_TAKEOFF_HEADING) { + magHold = nav_takeoff_bearing; + } + } + break; + } + } //end of gps calcs + } + } +} + +void GPS_reset_home_position(void) +{ + if (f.GPS_FIX && GPS_numSat >= 5) { + GPS_home[LAT] = GPS_coord[LAT]; + GPS_home[LON] = GPS_coord[LON]; + GPS_calc_longitude_scaling(GPS_coord[LAT]); // need an initial value for distance and bearing calc + nav_takeoff_bearing = heading; // save takeoff heading + // Set ground altitude + f.GPS_FIX_HOME = 1; + } +} + +//reset navigation (stop the navigation processor, and clear nav) +void GPS_reset_nav(void) +{ + int i; + + for (i = 0; i < 2; i++) { + GPS_angle[i] = 0; + nav_rated[i] = 0; + nav[i] = 0; + reset_PID(&posholdPID[i]); + reset_PID(&poshold_ratePID[i]); + reset_PID(&navPID[i]); + } +} + +//Get the relevant P I D values and set the PID controllers +static void GPS_set_pids(void) +{ + posholdPID_PARAM.kP = (float)cfg.P8[PIDPOS] / 100.0f; + posholdPID_PARAM.kI = (float)cfg.I8[PIDPOS] / 100.0f; + posholdPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100; + + poshold_ratePID_PARAM.kP = (float)cfg.P8[PIDPOSR] / 10.0f; + poshold_ratePID_PARAM.kI = (float)cfg.I8[PIDPOSR] / 100.0f; + poshold_ratePID_PARAM.kD = (float)cfg.D8[PIDPOSR] / 1000.0f; + poshold_ratePID_PARAM.Imax = POSHOLD_RATE_IMAX * 100; + + navPID_PARAM.kP = (float)cfg.P8[PIDNAVR] / 10.0f; + navPID_PARAM.kI = (float)cfg.I8[PIDNAVR] / 100.0f; + navPID_PARAM.kD = (float)cfg.D8[PIDNAVR] / 1000.0f; + navPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100; +} + +// OK here is the onboard GPS code + +//////////////////////////////////////////////////////////////////////////////////// +// PID based GPS navigation functions +// Author : EOSBandi +// Based on code and ideas from the Arducopter team: Jason Short,Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen +// Andrew Tridgell, Justin Beech, Adam Rivera, Jean-Louis Naudin, Roberto Navoni + +//////////////////////////////////////////////////////////////////////////////////// +// this is used to offset the shrinking longitude as we go towards the poles +// It's ok to calculate this once per waypoint setting, since it changes a little within the reach of a multicopter +// +static void GPS_calc_longitude_scaling(int32_t lat) +{ + float rads = (abs((float)lat) / 10000000.0f) * 0.0174532925f; + GPS_scaleLonDown = cosf(rads); +} + +//////////////////////////////////////////////////////////////////////////////////// +// Sets the waypoint to navigate, reset neccessary variables and calculate initial values +// +void GPS_set_next_wp(int32_t *lat, int32_t *lon) +{ + GPS_WP[LAT] = *lat; + GPS_WP[LON] = *lon; + + GPS_calc_longitude_scaling(*lat); + GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_WP[LAT], &GPS_WP[LON], &wp_distance, &target_bearing); + + nav_bearing = target_bearing; + GPS_calc_location_error(&GPS_WP[LAT], &GPS_WP[LON], &GPS_coord[LAT], &GPS_coord[LON]); + original_target_bearing = target_bearing; + waypoint_speed_gov = cfg.nav_speed_min; +} + +//////////////////////////////////////////////////////////////////////////////////// +// Check if we missed the destination somehow +// +static bool check_missed_wp(void) +{ + int32_t temp; + temp = target_bearing - original_target_bearing; + temp = wrap_18000(temp); + return (abs(temp) > 10000); // we passed the waypoint by 100 degrees +} + +//////////////////////////////////////////////////////////////////////////////////// +// Get distance between two points in cm +// Get bearing from pos1 to pos2, returns an 1deg = 100 precision +static void GPS_distance_cm_bearing(int32_t * lat1, int32_t * lon1, int32_t * lat2, int32_t * lon2, uint32_t * dist, int32_t * bearing) +{ + float dLat = *lat2 - *lat1; // difference of latitude in 1/10 000 000 degrees + float dLon = (float) (*lon2 - *lon1) * GPS_scaleLonDown; + *dist = sqrtf(sq(dLat) + sq(dLon)) * 1.113195f; + + *bearing = 9000.0f + atan2f(-dLat, dLon) * 5729.57795f; // Convert the output radians to 100xdeg + if (*bearing < 0) + *bearing += 36000; +} + +//////////////////////////////////////////////////////////////////////////////////// +// keep old calculation function for compatibility (could be removed later) distance in meters, bearing in degree +// +//static void GPS_distance(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2, uint16_t* dist, int16_t* bearing) { +// uint32_t d1; +// int32_t d2; +// GPS_distance_cm_bearing(&lat1,&lon1,&lat2,&lon2,&d1,&d2); +// *dist = d1 / 100; //convert to meters +// *bearing = d2 / 100; //convert to degrees +//} + +//////////////////////////////////////////////////////////////////////////////////// +// Calculate our current speed vector from gps position data +// +static void GPS_calc_velocity(void) +{ + static int16_t speed_old[2] = { 0, 0 }; + static int32_t last[2] = { 0, 0 }; + static uint8_t init = 0; + // y_GPS_speed positve = Up + // x_GPS_speed positve = Right + + if (init) { + float tmp = 1.0f / dTnav; + actual_speed[GPS_X] = (float) (GPS_coord[LON] - last[LON]) * GPS_scaleLonDown * tmp; + actual_speed[GPS_Y] = (float) (GPS_coord[LAT] - last[LAT]) * tmp; + + actual_speed[GPS_X] = (actual_speed[GPS_X] + speed_old[GPS_X]) / 2; + actual_speed[GPS_Y] = (actual_speed[GPS_Y] + speed_old[GPS_Y]) / 2; + + speed_old[GPS_X] = actual_speed[GPS_X]; + speed_old[GPS_Y] = actual_speed[GPS_Y]; + } + init = 1; + + last[LON] = GPS_coord[LON]; + last[LAT] = GPS_coord[LAT]; +} + +//////////////////////////////////////////////////////////////////////////////////// +// Calculate a location error between two gps coordinates +// Because we are using lat and lon to do our distance errors here's a quick chart: +// 100 = 1m +// 1000 = 11m = 36 feet +// 1800 = 19.80m = 60 feet +// 3000 = 33m +// 10000 = 111m +// +static void GPS_calc_location_error(int32_t *target_lat, int32_t *target_lng, int32_t *gps_lat, int32_t *gps_lng) +{ + error[LON] = (float) (*target_lng - *gps_lng) * GPS_scaleLonDown; // X Error + error[LAT] = *target_lat - *gps_lat; // Y Error +} + +//////////////////////////////////////////////////////////////////////////////////// +// Calculate nav_lat and nav_lon from the x and y error and the speed +// +static void GPS_calc_poshold(void) +{ + int32_t d; + int32_t target_speed; + int axis; + + for (axis = 0; axis < 2; axis++) { + target_speed = get_P(error[axis], &posholdPID_PARAM); // calculate desired speed from lon error + rate_error[axis] = target_speed - actual_speed[axis]; // calc the speed error + + nav[axis] = get_P(rate_error[axis], &poshold_ratePID_PARAM) + + get_I(rate_error[axis] + error[axis], &dTnav, &poshold_ratePID[axis], &poshold_ratePID_PARAM); + d = get_D(error[axis], &dTnav, &poshold_ratePID[axis], &poshold_ratePID_PARAM); + d = constrain(d, -2000, 2000); + + // get rid of noise +#if defined(GPS_LOW_SPEED_D_FILTER) + if (abs(actual_speed[axis]) < 50) + d = 0; +#endif + + nav[axis] +=d; + nav[axis] = constrain(nav[axis], -NAV_BANK_MAX, NAV_BANK_MAX); + navPID[axis].integrator = poshold_ratePID[axis].integrator; + } +} + +//////////////////////////////////////////////////////////////////////////////////// +// Calculate the desired nav_lat and nav_lon for distance flying such as RTH +// +static void GPS_calc_nav_rate(int max_speed) +{ + float trig[2]; + float temp; + int axis; + + // push us towards the original track + GPS_update_crosstrack(); + + // nav_bearing includes crosstrack + temp = (9000l - nav_bearing) * RADX100; + trig[GPS_X] = cosf(temp); + trig[GPS_Y] = sinf(temp); + + for (axis = 0; axis < 2; axis++) { + rate_error[axis] = (trig[axis] * max_speed) - actual_speed[axis]; + rate_error[axis] = constrain(rate_error[axis], -1000, 1000); + // P + I + D + nav[axis] = get_P(rate_error[axis], &navPID_PARAM) + + get_I(rate_error[axis], &dTnav, &navPID[axis], &navPID_PARAM) + + get_D(rate_error[axis], &dTnav, &navPID[axis], &navPID_PARAM); + + nav[axis] = constrain(nav[axis], -NAV_BANK_MAX, NAV_BANK_MAX); + poshold_ratePID[axis].integrator = navPID[axis].integrator; + } +} + +//////////////////////////////////////////////////////////////////////////////////// +// Calculating cross track error, this tries to keep the copter on a direct line +// when flying to a waypoint. +// +static void GPS_update_crosstrack(void) +{ + if (abs(wrap_18000(target_bearing - original_target_bearing)) < 4500) { // If we are too far off or too close we don't do track following + float temp = (target_bearing - original_target_bearing) * RADX100; + crosstrack_error = sinf(temp) * (wp_distance * CROSSTRACK_GAIN); // Meters we are off track line + nav_bearing = target_bearing + constrain(crosstrack_error, -3000, 3000); + nav_bearing = wrap_36000(nav_bearing); + } else { + nav_bearing = target_bearing; + } +} + +//////////////////////////////////////////////////////////////////////////////////// +// Determine desired speed when navigating towards a waypoint, also implement slow +// speed rampup when starting a navigation +// +// |< WP Radius +// 0 1 2 3 4 5 6 7 8m +// ...|...|...|...|...|...|...|...| +// 100 | 200 300 400cm/s +// | +|+ +// |< we should slow to 1.5 m/s as we hit the target +// +static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow) +{ + // max_speed is default 400 or 4m/s + if (_slow) { + max_speed = min(max_speed, wp_distance / 2); + } else { + max_speed = min(max_speed, wp_distance); + max_speed = max(max_speed, cfg.nav_speed_min); // go at least 100cm/s + } + + // limit the ramp up of the speed + // waypoint_speed_gov is reset to 0 at each new WP command + if (max_speed > waypoint_speed_gov) { + waypoint_speed_gov += (int) (100.0f * dTnav); // increase at .5/ms + max_speed = waypoint_speed_gov; + } + return max_speed; +} + +//////////////////////////////////////////////////////////////////////////////////// +// Utilities +// +int32_t wrap_18000(int32_t error) +{ + if (error > 18000) + error -= 36000; + if (error < -18000) + error += 36000; + return error; +} + +static int32_t wrap_36000(int32_t angle) +{ + if (angle > 36000) + angle -= 36000; + if (angle < 0) + angle += 36000; + return angle; +} + +// This code is used for parsing NMEA data + +/* Alex optimization + The latitude or longitude is coded this way in NMEA frames + dm.f coded as degrees + minutes + minute decimal + Where: + - d can be 1 or more char long. generally: 2 char long for latitude, 3 char long for longitude + - m is always 2 char long + - f can be 1 or more char long + This function converts this format in a unique unsigned long where 1 degree = 10 000 000 + + EOS increased the precision here, even if we think that the gps is not precise enough, with 10e5 precision it has 76cm resolution + with 10e7 it's around 1 cm now. Increasing it further is irrelevant, since even 1cm resolution is unrealistic, however increased + resolution also increased precision of nav calculations +static uint32_t GPS_coord_to_degrees(char *s) +{ + char *p = s, *d = s; + uint8_t min, deg = 0; + uint16_t frac = 0, mult = 10000; + + while (*p) { // parse the string until its end + if (d != s) { + frac += (*p - '0') * mult; // calculate only fractional part on up to 5 digits (d != s condition is true when the . is located) + mult /= 10; + } + if (*p == '.') + d = p; // locate '.' char in the string + p++; + } + if (p == s) + return 0; + while (s < d - 2) { + deg *= 10; // convert degrees : all chars before minutes ; for the first iteration, deg = 0 + deg += *(s++) - '0'; + } + min = *(d - 1) - '0' + (*(d - 2) - '0') * 10; // convert minutes : 2 previous char before '.' + return deg * 10000000UL + (min * 100000UL + frac) * 10UL / 6; +} +*/ + +#define DIGIT_TO_VAL(_x) (_x - '0') +uint32_t GPS_coord_to_degrees(char* s) +{ + char *p, *q; + uint8_t deg = 0, min = 0; + unsigned int frac_min = 0; + int i; + + // scan for decimal point or end of field + for (p = s; isdigit(*p); p++) + ; + q = s; + + // convert degrees + while ((p - q) > 2) { + if (deg) + deg *= 10; + deg += DIGIT_TO_VAL(*q++); + } + // convert minutes + while (p > q) { + if (min) + min *= 10; + min += DIGIT_TO_VAL(*q++); + } + // convert fractional minutes + // expect up to four digits, result is in + // ten-thousandths of a minute + if (*p == '.') { + q = p + 1; + for (i = 0; i < 4; i++) { + frac_min *= 10; + if (isdigit(*q)) + frac_min += *q++ - '0'; + } + } + return deg * 10000000UL + (min * 1000000UL + frac_min * 100UL) / 6; +} + +// helper functions +static uint32_t grab_fields(char *src, uint8_t mult) +{ // convert string to uint32 + uint32_t i; + uint32_t tmp = 0; + for (i = 0; src[i] != 0; i++) { + if (src[i] == '.') { + i++; + if (mult == 0) + break; + else + src[i + mult] = 0; + } + tmp *= 10; + if (src[i] >= '0' && src[i] <= '9') + tmp += src[i] - '0'; + } + return tmp; +} + +static uint8_t hex_c(uint8_t n) +{ // convert '0'..'9','A'..'F' to 0..15 + n -= '0'; + if (n > 9) + n -= 7; + n &= 0x0F; + return n; +} + +static bool GPS_newFrame(char c) +{ + switch (cfg.gps_type) { + case GPS_NMEA: // NMEA + case GPS_MTK: // MTK outputs NMEA too + return GPS_NMEA_newFrame(c); + case GPS_UBLOX: // UBX + return GPS_UBLOX_newFrame(c); + } + + return false; +} + +/* This is a light implementation of a GPS frame decoding + This should work with most of modern GPS devices configured to output NMEA frames. + It assumes there are some NMEA GGA frames to decode on the serial bus + Here we use only the following data : + - latitude + - longitude + - GPS fix is/is not ok + - GPS num sat (4 is enough to be +/- reliable) + // added by Mis + - GPS altitude (for OSD displaying) + - GPS speed (for OSD displaying) +*/ +#define FRAME_GGA 1 +#define FRAME_RMC 2 + +static bool GPS_NMEA_newFrame(char c) +{ + uint8_t frameOK = 0; + static uint8_t param = 0, offset = 0, parity = 0; + static char string[15]; + static uint8_t checksum_param, frame = 0; + + if (c == '$') { + param = 0; + offset = 0; + parity = 0; + } else if (c == ',' || c == '*') { + string[offset] = 0; + if (param == 0) { //frame identification + frame = 0; + if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A') + frame = FRAME_GGA; + if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C') + frame = FRAME_RMC; + } else if (frame == FRAME_GGA) { + if (param == 2) { + GPS_coord[LAT] = GPS_coord_to_degrees(string); + } else if (param == 3 && string[0] == 'S') + GPS_coord[LAT] = -GPS_coord[LAT]; + else if (param == 4) { + GPS_coord[LON] = GPS_coord_to_degrees(string); + } else if (param == 5 && string[0] == 'W') + GPS_coord[LON] = -GPS_coord[LON]; + else if (param == 6) { + f.GPS_FIX = string[0] > '0'; + } else if (param == 7) { + GPS_numSat = grab_fields(string, 0); + } else if (param == 9) { + GPS_altitude = grab_fields(string, 0); // altitude in meters added by Mis + } + } else if (frame == FRAME_RMC) { + if (param == 7) { + GPS_speed = (grab_fields(string, 1) * 5144L) / 1000L; // speed in cm/s added by Mis + } else if (param == 8) { + GPS_ground_course = grab_fields(string, 1); // ground course deg * 10 + } + } + param++; + offset = 0; + if (c == '*') + checksum_param = 1; + else + parity ^= c; + } else if (c == '\r' || c == '\n') { + if (checksum_param) { // parity checksum + uint8_t checksum = hex_c(string[0]); + checksum <<= 4; + checksum += hex_c(string[1]); + if (checksum == parity) + frameOK = 1; + } + checksum_param = 0; + } else { + if (offset < 15) + string[offset++] = c; + if (!checksum_param) + parity ^= c; + } + if (frame) + GPS_Present = 1; + return frameOK && (frame == FRAME_GGA); +} + + +// UBX support +typedef struct { + uint8_t preamble1; + uint8_t preamble2; + uint8_t msg_class; + uint8_t msg_id; + uint16_t length; +} ubx_header; + +typedef struct { + uint32_t time; // GPS msToW + int32_t longitude; + int32_t latitude; + int32_t altitude_ellipsoid; + int32_t altitude_msl; + uint32_t horizontal_accuracy; + uint32_t vertical_accuracy; +} ubx_nav_posllh; + +typedef struct { + uint32_t time; // GPS msToW + uint8_t fix_type; + uint8_t fix_status; + uint8_t differential_status; + uint8_t res; + uint32_t time_to_first_fix; + uint32_t uptime; // milliseconds +} ubx_nav_status; + +typedef struct { + uint32_t time; + int32_t time_nsec; + int16_t week; + uint8_t fix_type; + uint8_t fix_status; + int32_t ecef_x; + int32_t ecef_y; + int32_t ecef_z; + uint32_t position_accuracy_3d; + int32_t ecef_x_velocity; + int32_t ecef_y_velocity; + int32_t ecef_z_velocity; + uint32_t speed_accuracy; + uint16_t position_DOP; + uint8_t res; + uint8_t satellites; + uint32_t res2; +} ubx_nav_solution; + +typedef struct { + uint32_t time; // GPS msToW + int32_t ned_north; + int32_t ned_east; + int32_t ned_down; + uint32_t speed_3d; + uint32_t speed_2d; + int32_t heading_2d; + uint32_t speed_accuracy; + uint32_t heading_accuracy; +} ubx_nav_velned; + +enum { + PREAMBLE1 = 0xb5, + PREAMBLE2 = 0x62, + CLASS_NAV = 0x01, + CLASS_ACK = 0x05, + CLASS_CFG = 0x06, + MSG_ACK_NACK = 0x00, + MSG_ACK_ACK = 0x01, + MSG_POSLLH = 0x2, + MSG_STATUS = 0x3, + MSG_SOL = 0x6, + MSG_VELNED = 0x12, + MSG_CFG_PRT = 0x00, + MSG_CFG_RATE = 0x08, + MSG_CFG_SET_RATE = 0x01, + MSG_CFG_NAV_SETTINGS = 0x24 +} ubs_protocol_bytes; + +enum { + FIX_NONE = 0, + FIX_DEAD_RECKONING = 1, + FIX_2D = 2, + FIX_3D = 3, + FIX_GPS_DEAD_RECKONING = 4, + FIX_TIME = 5 +} ubs_nav_fix_type; + +enum { + NAV_STATUS_FIX_VALID = 1 +} ubx_nav_status_bits; + +// Packet checksum accumulators +static uint8_t _ck_a; +static uint8_t _ck_b; + +// State machine state +static uint8_t _step; +static uint8_t _msg_id; +static uint16_t _payload_length; +static uint16_t _payload_counter; + +static bool next_fix; +static uint8_t _class; + +// do we have new position information? +static bool _new_position; + +// do we have new speed information? +static bool _new_speed; + +static uint8_t _disable_counter; + +// Receive buffer +static union { + ubx_nav_posllh posllh; + ubx_nav_status status; + ubx_nav_solution solution; + ubx_nav_velned velned; + uint8_t bytes[64]; +} _buffer; + +void _update_checksum(uint8_t *data, uint8_t len, uint8_t *ck_a, uint8_t *ck_b) +{ + while (len--) { + *ck_a += *data; + *ck_b += *ck_a; + data++; + } +} + +static bool GPS_UBLOX_newFrame(uint8_t data) +{ + bool parsed = false; + + switch (_step) { + case 1: + if (PREAMBLE2 == data) { + _step++; + break; + } + _step = 0; + case 0: + if (PREAMBLE1 == data) + _step++; + break; + case 2: + _step++; + _class = data; + _ck_b = _ck_a = data; // reset the checksum accumulators + break; + case 3: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _msg_id = data; + break; + case 4: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _payload_length = data; // payload length low byte + break; + case 5: + _step++; + _ck_b += (_ck_a += data); // checksum byte + _payload_length += (uint16_t) (data << 8); + if (_payload_length > 512) { + _payload_length = 0; + _step = 0; + } + _payload_counter = 0; // prepare to receive payload + break; + case 6: + _ck_b += (_ck_a += data); // checksum byte + if (_payload_counter < sizeof(_buffer)) { + _buffer.bytes[_payload_counter] = data; + } + if (++_payload_counter == _payload_length) + _step++; + break; + case 7: + _step++; + if (_ck_a != data) + _step = 0; // bad checksum + break; + case 8: + _step = 0; + if (_ck_b != data) + break; // bad checksum + GPS_Present = 1; + if (UBLOX_parse_gps()) { + parsed = true; + } + } //end switch + return parsed; +} + +static bool UBLOX_parse_gps(void) +{ + switch (_msg_id) { + case MSG_POSLLH: + //i2c_dataset.time = _buffer.posllh.time; + GPS_coord[LON] = _buffer.posllh.longitude; + GPS_coord[LAT] = _buffer.posllh.latitude; + GPS_altitude = _buffer.posllh.altitude_msl / 10 / 100; //alt in m + f.GPS_FIX = next_fix; + _new_position = true; + break; + case MSG_STATUS: + next_fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D); + if (!next_fix) + f.GPS_FIX = false; + break; + case MSG_SOL: + next_fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D); + if (!next_fix) + f.GPS_FIX = false; + GPS_numSat = _buffer.solution.satellites; + // GPS_hdop = _buffer.solution.position_DOP; + // debug[3] = GPS_hdop; + break; + case MSG_VELNED: + // speed_3d = _buffer.velned.speed_3d; // cm/s + GPS_speed = _buffer.velned.speed_2d; // cm/s + GPS_ground_course = (uint16_t) (_buffer.velned.heading_2d / 10000); // Heading 2D deg * 100000 rescaled to deg * 10 + _new_speed = true; + break; + default: + return false; + } + + // we only return true when we get new position and speed data + // this ensures we don't use stale data + if (_new_position && _new_speed) { + _new_speed = _new_position = false; + return true; + } + return false; +} diff --git a/src/baseflight/src/imu.c b/src/baseflight/src/imu.c new file mode 100755 index 0000000000..73d9a7072e --- /dev/null +++ b/src/baseflight/src/imu.c @@ -0,0 +1,411 @@ +#include "board.h" +#include "mw.h" + +int16_t gyroADC[3], accADC[3], accSmooth[3], magADC[3]; +float accLPFVel[3]; +int16_t acc_25deg = 0; +int32_t BaroAlt; +int16_t sonarAlt; //to think about the unit +int32_t EstAlt; // in cm +int16_t BaroPID = 0; +int32_t AltHold; +int16_t errorAltitudeI = 0; +float magneticDeclination = 0.0f; // calculated at startup from config +float accVelScale; + +// ************** +// gyro+acc IMU +// ************** +int16_t gyroData[3] = { 0, 0, 0 }; +int16_t gyroZero[3] = { 0, 0, 0 }; +int16_t angle[2] = { 0, 0 }; // absolute angle inclination in multiple of 0.1 degree 180 deg = 1800 + +static void getEstimatedAttitude(void); + +void imuInit(void) +{ + acc_25deg = acc_1G * 0.423f; + accVelScale = 9.80665f / acc_1G / 10000.0f; + +#ifdef MAG + // if mag sensor is enabled, use it + if (sensors(SENSOR_MAG)) + Mag_init(); +#endif +} + + +void computeIMU(void) +{ + uint32_t axis; + static int16_t gyroADCprevious[3] = { 0, 0, 0 }; + int16_t gyroADCp[3]; + int16_t gyroADCinter[3]; + static uint32_t timeInterleave = 0; + static int16_t gyroYawSmooth = 0; + +#define GYRO_INTERLEAVE + + if (sensors(SENSOR_ACC)) { + ACC_getADC(); + getEstimatedAttitude(); + } + + Gyro_getADC(); + + for (axis = 0; axis < 3; axis++) { +#ifdef GYRO_INTERLEAVE + gyroADCp[axis] = gyroADC[axis]; +#else + gyroData[axis] = gyroADC[axis]; +#endif + if (!sensors(SENSOR_ACC)) + accADC[axis] = 0; + } + timeInterleave = micros(); + annexCode(); +#ifdef GYRO_INTERLEAVE + if ((micros() - timeInterleave) > 650) { + annex650_overrun_count++; + } else { + while ((micros() - timeInterleave) < 650); // empirical, interleaving delay between 2 consecutive reads + } + + Gyro_getADC(); + for (axis = 0; axis < 3; axis++) { + gyroADCinter[axis] = gyroADC[axis] + gyroADCp[axis]; + // empirical, we take a weighted value of the current and the previous values + gyroData[axis] = (gyroADCinter[axis] + gyroADCprevious[axis]) / 3; + gyroADCprevious[axis] = gyroADCinter[axis] / 2; + if (!sensors(SENSOR_ACC)) + accADC[axis] = 0; + } +#endif + + if (feature(FEATURE_GYRO_SMOOTHING)) { + static uint8_t Smoothing[3] = { 0, 0, 0 }; + static int16_t gyroSmooth[3] = { 0, 0, 0 }; + if (Smoothing[0] == 0) { + // initialize + Smoothing[ROLL] = (cfg.gyro_smoothing_factor >> 16) & 0xff; + Smoothing[PITCH] = (cfg.gyro_smoothing_factor >> 8) & 0xff; + Smoothing[YAW] = (cfg.gyro_smoothing_factor) & 0xff; + } + for (axis = 0; axis < 3; axis++) { + gyroData[axis] = (int16_t)(((int32_t)((int32_t)gyroSmooth[axis] * (Smoothing[axis] - 1)) + gyroData[axis] + 1 ) / Smoothing[axis]); + gyroSmooth[axis] = gyroData[axis]; + } + } else if (cfg.mixerConfiguration == MULTITYPE_TRI) { + gyroData[YAW] = (gyroYawSmooth * 2 + gyroData[YAW]) / 3; + gyroYawSmooth = gyroData[YAW]; + } +} + +// ************************************************** +// Simplified IMU based on "Complementary Filter" +// Inspired by http://starlino.com/imu_guide.html +// +// adapted by ziss_dm : http://www.multiwii.com/forum/viewtopic.php?f=8&t=198 +// +// The following ideas was used in this project: +// 1) Rotation matrix: http://en.wikipedia.org/wiki/Rotation_matrix +// 2) Small-angle approximation: http://en.wikipedia.org/wiki/Small-angle_approximation +// 3) C. Hastings approximation for atan2() +// 4) Optimization tricks: http://www.hackersdelight.org/ +// +// Currently Magnetometer uses separate CF which is used only +// for heading approximation. +// +// Modified: 19/04/2011 by ziss_dm +// Version: V1.1 +// +// code size deduction and tmp vector intermediate step for vector rotation computation: October 2011 by Alex +// ************************************************** + +//****** advanced users settings ******************* + +/* Set the Low Pass Filter factor for Magnetometer */ +/* Increasing this value would reduce Magnetometer noise (not visible in GUI), but would increase Magnetometer lag time*/ +/* Comment this if you do not want filter at all.*/ +/* Default WMC value: n/a*/ +//#define MG_LPF_FACTOR 4 + +/* Set the Gyro Weight for Gyro/Magnetometer complementary filter */ +/* Increasing this value would reduce and delay Magnetometer influence on the output of the filter*/ +/* Default WMC value: n/a*/ +#define GYR_CMPFM_FACTOR 200.0f + +//****** end of advanced users settings ************* + +#define INV_GYR_CMPF_FACTOR (1.0f / ((float)cfg.gyro_cmpf_factor + 1.0f)) +#define INV_GYR_CMPFM_FACTOR (1.0f / (GYR_CMPFM_FACTOR + 1.0f)) + +#define GYRO_SCALE ((1998 * M_PI)/((32767.0f / 4.0f ) * 180.0f * 1000000.0f)) // 32767 / 16.4lsb/dps for MPU3000 + +// #define GYRO_SCALE ((2380 * M_PI)/((32767.0f / 4.0f ) * 180.0f * 1000000.0f)) //should be 2279.44 but 2380 gives better result (ITG-3200) + // +-2000/sec deg scale + //#define GYRO_SCALE ((200.0f * PI)/((32768.0f / 5.0f / 4.0f ) * 180.0f * 1000000.0f) * 1.5f) + // +- 200/sec deg scale + // 1.5 is emperical, not sure what it means + // should be in rad/sec + +typedef struct fp_vector { + float X; + float Y; + float Z; +} t_fp_vector_def; + +typedef union { + float A[3]; + t_fp_vector_def V; +} t_fp_vector; + +t_fp_vector EstG; + +// Rotate Estimated vector(s) with small angle approximation, according to the gyro data +void rotateV(struct fp_vector *v, float *delta) +{ + struct fp_vector v_tmp = *v; + +#if INACCURATE + v->Z -= delta[ROLL] * v_tmp.X + delta[PITCH] * v_tmp.Y; + v->X += delta[ROLL] * v_tmp.Z - delta[YAW] * v_tmp.Y; + v->Y += delta[PITCH] * v_tmp.Z + delta[YAW] * v_tmp.X; +#else + // This does a "proper" matrix rotation using gyro deltas without small-angle approximation + float mat[3][3]; + float cosx, sinx, cosy, siny, cosz, sinz; + float coszcosx, coszcosy, sinzcosx, coszsinx, sinzsinx; + + cosx = cosf(-delta[PITCH]); + sinx = sinf(-delta[PITCH]); + cosy = cosf(delta[ROLL]); + siny = sinf(delta[ROLL]); + cosz = cosf(delta[YAW]); + sinz = sinf(delta[YAW]); + + coszcosx = cosz * cosx; + coszcosy = cosz * cosy; + sinzcosx = sinz * cosx; + coszsinx = sinx * cosz; + sinzsinx = sinx * sinz; + + mat[0][0] = coszcosy; + mat[0][1] = sinz * cosy; + mat[0][2] = -siny; + mat[1][0] = (coszsinx * siny) - sinzcosx; + mat[1][1] = (sinzsinx * siny) + (coszcosx); + mat[1][2] = cosy * sinx; + mat[2][0] = (coszcosx * siny) + (sinzsinx); + mat[2][1] = (sinzcosx * siny) - (coszsinx); + mat[2][2] = cosy * cosx; + + v->X = v_tmp.X * mat[0][0] + v_tmp.Y * mat[1][0] + v_tmp.Z * mat[2][0]; + v->Y = v_tmp.X * mat[0][1] + v_tmp.Y * mat[1][1] + v_tmp.Z * mat[2][1]; + v->Z = v_tmp.X * mat[0][2] + v_tmp.Y * mat[1][2] + v_tmp.Z * mat[2][2]; +#endif +} + +static int16_t _atan2f(float y, float x) +{ + // no need for aidsy inaccurate shortcuts on a proper platform + return (int16_t)(atan2f(y, x) * (180.0f / M_PI * 10.0f)); +} + +static void getEstimatedAttitude(void) +{ + uint32_t axis; + int32_t accMag = 0; + static t_fp_vector EstM; +#if defined(MG_LPF_FACTOR) + static int16_t mgSmooth[3]; +#endif + static float accLPF[3]; + static uint32_t previousT; + uint32_t currentT = micros(); + float scale, deltaGyroAngle[3]; + + scale = (currentT - previousT) * GYRO_SCALE; + previousT = currentT; + + // Initialization + for (axis = 0; axis < 3; axis++) { + deltaGyroAngle[axis] = gyroADC[axis] * scale; + if (cfg.acc_lpf_factor > 0) { + accLPF[axis] = accLPF[axis] * (1.0f - (1.0f / cfg.acc_lpf_factor)) + accADC[axis] * (1.0f / cfg.acc_lpf_factor); + accSmooth[axis] = accLPF[axis]; + } else { + accSmooth[axis] = accADC[axis]; + } + accLPFVel[axis] = accLPFVel[axis] * (1.0f - (1.0f / cfg.acc_lpf_for_velocity)) + accADC[axis] * (1.0f / cfg.acc_lpf_for_velocity); + accMag += (int32_t)accSmooth[axis] * accSmooth[axis]; + + if (sensors(SENSOR_MAG)) { +#if defined(MG_LPF_FACTOR) + mgSmooth[axis] = (mgSmooth[axis] * (MG_LPF_FACTOR - 1) + magADC[axis]) / MG_LPF_FACTOR; // LPF for Magnetometer values +#define MAG_VALUE mgSmooth[axis] +#else +#define MAG_VALUE magADC[axis] +#endif + } + } + accMag = accMag * 100 / ((int32_t)acc_1G * acc_1G); + + rotateV(&EstG.V, deltaGyroAngle); + if (sensors(SENSOR_MAG)) + rotateV(&EstM.V, deltaGyroAngle); + + if (abs(accSmooth[ROLL]) < acc_25deg && abs(accSmooth[PITCH]) < acc_25deg && accSmooth[YAW] > 0) + f.SMALL_ANGLES_25 = 1; + else + f.SMALL_ANGLES_25 = 0; + + // Apply complimentary filter (Gyro drift correction) + // If accel magnitude >1.4G or <0.6G and ACC vector outside of the limit range => we neutralize the effect of accelerometers in the angle estimation. + // To do that, we just skip filter, as EstV already rotated by Gyro + if ((36 < accMag && accMag < 196) || f.SMALL_ANGLES_25) { + for (axis = 0; axis < 3; axis++) + EstG.A[axis] = (EstG.A[axis] * (float)cfg.gyro_cmpf_factor + accSmooth[axis]) * INV_GYR_CMPF_FACTOR; + } + + if (sensors(SENSOR_MAG)) { + for (axis = 0; axis < 3; axis++) + EstM.A[axis] = (EstM.A[axis] * GYR_CMPFM_FACTOR + MAG_VALUE) * INV_GYR_CMPFM_FACTOR; + } + + // Attitude of the estimated vector +#if INACCURATE + angle[ROLL] = _atan2f(EstG.V.X, EstG.V.Z); + angle[PITCH] = _atan2f(EstG.V.Y, EstG.V.Z); +#else + // This hack removes gimbal lock (sorta) on pitch, so rolling around doesn't make pitch jump when roll reaches 90deg + angle[ROLL] = _atan2f(EstG.V.X, EstG.V.Z); + angle[PITCH] = -asinf(EstG.V.Y / -sqrtf(EstG.V.X * EstG.V.X + EstG.V.Y * EstG.V.Y + EstG.V.Z * EstG.V.Z)) * (180.0f / M_PI * 10.0f); +#endif + +#ifdef MAG + if (sensors(SENSOR_MAG)) { + // Attitude of the cross product vector GxM + heading = _atan2f(EstG.V.X * EstM.V.Z - EstG.V.Z * EstM.V.X, EstG.V.Z * EstM.V.Y - EstG.V.Y * EstM.V.Z); + heading = heading + magneticDeclination; + heading = heading / 10; + + if (heading > 180) + heading = heading - 360; + else if (heading < -180) + heading = heading + 360; + } +#endif +} + +#ifdef BARO +#define UPDATE_INTERVAL 25000 // 40hz update rate (20hz LPF on acc) +#define INIT_DELAY 4000000 // 4 sec initialization delay + +int16_t applyDeadband16(int16_t value, int16_t deadband) +{ + if (abs(value) < deadband) { + value = 0; + } else if (value > 0) { + value -= deadband; + } else if (value < 0) { + value += deadband; + } + return value; +} + +float applyDeadbandFloat(float value, int16_t deadband) +{ + if (abs(value) < deadband) { + value = 0; + } else if (value > 0) { + value -= deadband; + } else if (value < 0) { + value += deadband; + } + return value; +} + +float InvSqrt(float x) +{ + union { + int32_t i; + float f; + } conv; + conv.f = x; + conv.i = 0x5f3759df - (conv.i >> 1); + return 0.5f * conv.f * (3.0f - x * conv.f * conv.f); +} + +int32_t isq(int32_t x) +{ + return x * x; +} + +void getEstimatedAltitude(void) +{ + static uint32_t deadLine = INIT_DELAY; + static int16_t baroHistTab[BARO_TAB_SIZE_MAX]; + static int8_t baroHistIdx; + static int32_t baroHigh; + uint32_t dTime; + int16_t error; + float invG; + int16_t accZ; + static float vel = 0.0f; + static int32_t lastBaroAlt; + float baroVel; + + if ((int32_t)(currentTime - deadLine) < UPDATE_INTERVAL) + return; + dTime = currentTime - deadLine; + deadLine = currentTime; + + // **** Alt. Set Point stabilization PID **** + baroHistTab[baroHistIdx] = BaroAlt / 10; + baroHigh += baroHistTab[baroHistIdx]; + baroHigh -= baroHistTab[(baroHistIdx + 1) % cfg.baro_tab_size]; + + baroHistIdx++; + if (baroHistIdx == cfg.baro_tab_size) + baroHistIdx = 0; + + EstAlt = EstAlt * cfg.baro_noise_lpf + (baroHigh * 10.0f / (cfg.baro_tab_size - 1)) * (1.0f - cfg.baro_noise_lpf); // additional LPF to reduce baro noise + + // P + error = constrain(AltHold - EstAlt, -300, 300); + error = applyDeadband16(error, 10); // remove small P parametr to reduce noise near zero position + BaroPID = constrain((cfg.P8[PIDALT] * error / 100), -150, +150); + + // I + errorAltitudeI += error * cfg.I8[PIDALT] / 50; + errorAltitudeI = constrain(errorAltitudeI, -30000, 30000); + BaroPID += (errorAltitudeI / 500); // I in range +/-60 + + // projection of ACC vector to global Z, with 1G subtructed + // Math: accZ = A * G / |G| - 1G + invG = InvSqrt(isq(EstG.V.X) + isq(EstG.V.Y) + isq(EstG.V.Z)); + accZ = (accLPFVel[ROLL] * EstG.V.X + accLPFVel[PITCH] * EstG.V.Y + accLPFVel[YAW] * EstG.V.Z) * invG - acc_1G; + accZ = applyDeadband16(accZ, acc_1G / cfg.accz_deadband); + debug[0] = accZ; + + // Integrator - velocity, cm/sec + vel += accZ * accVelScale * dTime; + + baroVel = (EstAlt - lastBaroAlt) / (dTime / 1000000.0f); + baroVel = constrain(baroVel, -300, 300); // constrain baro velocity +/- 300cm/s + baroVel = applyDeadbandFloat(baroVel, 10); // to reduce noise near zero + lastBaroAlt = EstAlt; + debug[1] = baroVel; + + // apply Complimentary Filter to keep near zero caluculated velocity based on baro velocity + vel = vel * cfg.baro_cf + baroVel * (1.0f - cfg.baro_cf); + // vel = constrain(vel, -300, 300); // constrain velocity +/- 300cm/s + debug[2] = vel; + // debug[3] = applyDeadbandFloat(vel, 5); + + // D + BaroPID -= constrain(cfg.D8[PIDALT] * applyDeadbandFloat(vel, 5) / 20, -150, 150); + debug[3] = BaroPID; +} +#endif /* BARO */ diff --git a/src/baseflight/src/main.c b/src/baseflight/src/main.c new file mode 100755 index 0000000000..8d4972e4a2 --- /dev/null +++ b/src/baseflight/src/main.c @@ -0,0 +1,156 @@ +#include "board.h" +#include "mw.h" + +extern uint8_t useServo; +extern rcReadRawDataPtr rcReadRawFunc; + +// two receiver read functions +extern uint16_t pwmReadRawRC(uint8_t chan); +extern uint16_t spektrumReadRawRC(uint8_t chan); + +static void _putc(void *p, char c) +{ + uartWrite(c); +} + + +int main(void) +{ + uint8_t i; + drv_pwm_config_t pwm_params; + drv_adc_config_t adc_params; + +#if 0 + // PC12, PA15 + // using this to write asm for bootloader :) + RCC->APB2ENR |= RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOC | RCC_APB2Periph_AFIO; // GPIOA/C+AFIO only + AFIO->MAPR &= 0xF0FFFFFF; + AFIO->MAPR = 0x02000000; + GPIOA->CRH = 0x34444444; // PIN 15 Output 50MHz + GPIOA->BRR = 0x8000; // set low 15 + GPIOC->CRH = 0x44434444; // PIN 12 Output 50MHz + GPIOC->BRR = 0x1000; // set low 12 +#endif + +#if 0 + // using this to write asm for bootloader :) + RCC->APB2ENR |= RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO; // GPIOB + AFIO + AFIO->MAPR &= 0xF0FFFFFF; + AFIO->MAPR = 0x02000000; + GPIOB->BRR = 0x18; // set low 4 & 3 + GPIOB->CRL = 0x44433444; // PIN 4 & 3 Output 50MHz +#endif + + systemInit(); + init_printf(NULL, _putc); + + checkFirstTime(false); + readEEPROM(); + + // configure power ADC + if (cfg.power_adc_channel > 0 && (cfg.power_adc_channel == 1 || cfg.power_adc_channel == 9)) + adc_params.powerAdcChannel = cfg.power_adc_channel; + else { + adc_params.powerAdcChannel = 0; + cfg.power_adc_channel = 0; + } + + adcInit(&adc_params); + + serialInit(cfg.serial_baudrate); + + // We have these sensors +#ifndef FY90Q + // AfroFlight32 + sensorsSet(SENSOR_ACC | SENSOR_BARO | SENSOR_MAG); +#else + // FY90Q + sensorsSet(SENSOR_ACC); +#endif + + mixerInit(); // this will set useServo var depending on mixer type + // when using airplane/wing mixer, servo/motor outputs are remapped + if (cfg.mixerConfiguration == MULTITYPE_AIRPLANE || cfg.mixerConfiguration == MULTITYPE_FLYING_WING) + pwm_params.airplane = true; + else + pwm_params.airplane = false; + pwm_params.useUART = feature(FEATURE_GPS) || feature(FEATURE_SPEKTRUM); // spektrum support uses UART too + pwm_params.usePPM = feature(FEATURE_PPM); + pwm_params.enableInput = !feature(FEATURE_SPEKTRUM); // disable inputs if using spektrum + pwm_params.useServos = useServo; + pwm_params.extraServos = cfg.gimbal_flags & GIMBAL_FORWARDAUX; + pwm_params.motorPwmRate = cfg.motor_pwm_rate; + pwm_params.servoPwmRate = cfg.servo_pwm_rate; + switch (cfg.power_adc_channel) { + case 1: + pwm_params.adcChannel = PWM2; + break; + case 9: + pwm_params.adcChannel = PWM8; + break; + default: + pwm_params.adcChannel = 0; + break; + } + + pwmInit(&pwm_params); + + // configure PWM/CPPM read function. spektrum below will override that + rcReadRawFunc = pwmReadRawRC; + + if (feature(FEATURE_SPEKTRUM)) { + spektrumInit(); + rcReadRawFunc = spektrumReadRawRC; + } else { + // spektrum and GPS are mutually exclusive + // Optional GPS - available in both PPM and PWM input mode, in PWM input, reduces number of available channels by 2. + if (feature(FEATURE_GPS)) + gpsInit(cfg.gps_baudrate); + } +#ifdef SONAR + // sonar stuff only works with PPM + if (feature(FEATURE_PPM)) { + if (feature(FEATURE_SONAR)) + Sonar_init(); + } +#endif + + LED1_ON; + LED0_OFF; + for (i = 0; i < 10; i++) { + LED1_TOGGLE; + LED0_TOGGLE; + delay(25); + BEEP_ON; + delay(25); + BEEP_OFF; + } + LED0_OFF; + LED1_OFF; + + // drop out any sensors that don't seem to work, init all the others. halt if gyro is dead. + sensorsAutodetect(); + imuInit(); // Mag is initialized inside imuInit + + // Check battery type/voltage + if (feature(FEATURE_VBAT)) + batteryInit(); + + previousTime = micros(); + if (cfg.mixerConfiguration == MULTITYPE_GIMBAL) + calibratingA = 400; + calibratingG = 1000; + f.SMALL_ANGLES_25 = 1; + + // loopy + while (1) { + loop(); + } +} + +void HardFault_Handler(void) +{ + // fall out of the sky + writeAllMotors(cfg.mincommand); + while (1); +} diff --git a/src/baseflight/src/mixer.c b/src/baseflight/src/mixer.c new file mode 100755 index 0000000000..34fee3dbdc --- /dev/null +++ b/src/baseflight/src/mixer.c @@ -0,0 +1,387 @@ +#include "board.h" +#include "mw.h" + +static uint8_t numberMotor = 0; +uint8_t useServo = 0; +int16_t motor[MAX_MOTORS]; +int16_t servo[8] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 }; + +static motorMixer_t currentMixer[MAX_MOTORS]; + +static const motorMixer_t mixerTri[] = { + { 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR + { 1.0f, -1.0f, -0.666667f, 0.0f }, // RIGHT + { 1.0f, 1.0f, -0.666667f, 0.0f }, // LEFT +}; + +static const motorMixer_t mixerQuadP[] = { + { 1.0f, 0.0f, 1.0f, -1.0f }, // REAR + { 1.0f, -1.0f, 0.0f, 1.0f }, // RIGHT + { 1.0f, 1.0f, 0.0f, 1.0f }, // LEFT + { 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT +}; + +static const motorMixer_t mixerQuadX[] = { + { 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R + { 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R + { 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L + { 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L +}; + +static const motorMixer_t mixerBi[] = { + { 1.0f, 1.0f, 0.0f, 0.0f }, // LEFT + { 1.0f, -1.0f, 0.0f, 0.0f }, // RIGHT +}; + +static const motorMixer_t mixerY6[] = { + { 1.0f, 0.0f, 1.333333f, 1.0f }, // REAR + { 1.0f, -1.0f, -0.666667f, -1.0f }, // RIGHT + { 1.0f, 1.0f, -0.666667f, -1.0f }, // LEFT + { 1.0f, 0.0f, 1.333333f, -1.0f }, // UNDER_REAR + { 1.0f, -1.0f, -0.666667f, 1.0f }, // UNDER_RIGHT + { 1.0f, 1.0f, -0.666667f, 1.0f }, // UNDER_LEFT +}; + +static const motorMixer_t mixerHex6P[] = { + { 1.0f, -1.0f, 0.866025f, 1.0f }, // REAR_R + { 1.0f, -1.0f, -0.866025f, -1.0f }, // FRONT_R + { 1.0f, 1.0f, 0.866025f, 1.0f }, // REAR_L + { 1.0f, 1.0f, -0.866025f, -1.0f }, // FRONT_L + { 1.0f, 0.0f, -0.866025f, 1.0f }, // FRONT + { 1.0f, 0.0f, 0.866025f, -1.0f }, // REAR +}; + +static const motorMixer_t mixerY4[] = { + { 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_TOP CW + { 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R CCW + { 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_BOTTOM CCW + { 1.0f, 1.0f, -1.0f, 0.0f }, // FRONT_L CW +}; + +static const motorMixer_t mixerHex6X[] = { + { 1.0f, -0.866025f, 1.0f, 1.0f }, // REAR_R + { 1.0f, -0.866025f, -1.0f, 1.0f }, // FRONT_R + { 1.0f, 0.866025f, 1.0f, -1.0f }, // REAR_L + { 1.0f, 0.866025f, -1.0f, -1.0f }, // FRONT_L + { 1.0f, -0.866025f, 0.0f, -1.0f }, // RIGHT + { 1.0f, 0.866025f, 0.0f, 1.0f }, // LEFT +}; + +static const motorMixer_t mixerOctoX8[] = { + { 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R + { 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R + { 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L + { 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L + { 1.0f, -1.0f, 1.0f, 1.0f }, // UNDER_REAR_R + { 1.0f, -1.0f, -1.0f, -1.0f }, // UNDER_FRONT_R + { 1.0f, 1.0f, 1.0f, -1.0f }, // UNDER_REAR_L + { 1.0f, 1.0f, -1.0f, 1.0f }, // UNDER_FRONT_L +}; + +static const motorMixer_t mixerOctoFlatP[] = { + { 1.0f, 0.707107f, -0.707107f, 1.0f }, // FRONT_L + { 1.0f, -0.707107f, -0.707107f, 1.0f }, // FRONT_R + { 1.0f, -0.707107f, 0.707107f, 1.0f }, // REAR_R + { 1.0f, 0.707107f, 0.707107f, 1.0f }, // REAR_L + { 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT + { 1.0f, -1.0f, 0.0f, -1.0f }, // RIGHT + { 1.0f, 0.0f, 1.0f, -1.0f }, // REAR + { 1.0f, 1.0f, 0.0f, -1.0f }, // LEFT +}; + +static const motorMixer_t mixerOctoFlatX[] = { + { 1.0f, 1.0f, -0.5f, 1.0f }, // MIDFRONT_L + { 1.0f, -0.5f, -1.0f, 1.0f }, // FRONT_R + { 1.0f, -1.0f, 0.5f, 1.0f }, // MIDREAR_R + { 1.0f, 0.5f, 1.0f, 1.0f }, // REAR_L + { 1.0f, 0.5f, -1.0f, -1.0f }, // FRONT_L + { 1.0f, -1.0f, -0.5f, -1.0f }, // MIDFRONT_R + { 1.0f, -0.5f, 1.0f, -1.0f }, // REAR_R + { 1.0f, 1.0f, 0.5f, -1.0f }, // MIDREAR_L +}; + +static const motorMixer_t mixerVtail4[] = { + { 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_R + { 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R + { 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_L + { 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L +}; + +// Keep this synced with MultiType struct in mw.h! +const mixer_t mixers[] = { +// Mo Se Mixtable + { 0, 0, NULL }, // entry 0 + { 3, 1, mixerTri }, // MULTITYPE_TRI + { 4, 0, mixerQuadP }, // MULTITYPE_QUADP + { 4, 0, mixerQuadX }, // MULTITYPE_QUADX + { 2, 1, mixerBi }, // MULTITYPE_BI + { 0, 1, NULL }, // * MULTITYPE_GIMBAL + { 6, 0, mixerY6 }, // MULTITYPE_Y6 + { 6, 0, mixerHex6P }, // MULTITYPE_HEX6 + { 1, 1, NULL }, // * MULTITYPE_FLYING_WING + { 4, 0, mixerY4 }, // MULTITYPE_Y4 + { 6, 0, mixerHex6X }, // MULTITYPE_HEX6X + { 8, 0, mixerOctoX8 }, // MULTITYPE_OCTOX8 + { 8, 0, mixerOctoFlatP }, // MULTITYPE_OCTOFLATP + { 8, 0, mixerOctoFlatX }, // MULTITYPE_OCTOFLATX + { 1, 1, NULL }, // * MULTITYPE_AIRPLANE + { 0, 1, NULL }, // * MULTITYPE_HELI_120_CCPM + { 0, 1, NULL }, // * MULTITYPE_HELI_90_DEG + { 4, 0, mixerVtail4 }, // MULTITYPE_VTAIL4 + { 0, 0, NULL }, // MULTITYPE_CUSTOM +}; + +void mixerInit(void) +{ + int i; + + // enable servos for mixes that require them. note, this shifts motor counts. + useServo = mixers[cfg.mixerConfiguration].useServo; + // if we want camstab/trig, that also enables servos, even if mixer doesn't + if (feature(FEATURE_SERVO_TILT)) + useServo = 1; + + if (cfg.mixerConfiguration == MULTITYPE_CUSTOM) { + // load custom mixer into currentMixer + for (i = 0; i < MAX_MOTORS; i++) { + // check if done + if (cfg.customMixer[i].throttle == 0.0f) + break; + currentMixer[i] = cfg.customMixer[i]; + numberMotor++; + } + } else { + numberMotor = mixers[cfg.mixerConfiguration].numberMotor; + // copy motor-based mixers + if (mixers[cfg.mixerConfiguration].motor) { + for (i = 0; i < numberMotor; i++) + currentMixer[i] = mixers[cfg.mixerConfiguration].motor[i]; + } + } +} + +void mixerLoadMix(int index) +{ + int i; + + // we're 1-based + index++; + // clear existing + for (i = 0; i < MAX_MOTORS; i++) + cfg.customMixer[i].throttle = 0.0f; + + // do we have anything here to begin with? + if (mixers[index].motor != NULL) { + for (i = 0; i < mixers[index].numberMotor; i++) + cfg.customMixer[i] = mixers[index].motor[i]; + } +} + +void writeServos(void) +{ + if (!useServo) + return; + + switch (cfg.mixerConfiguration) { + case MULTITYPE_BI: + pwmWriteServo(0, servo[4]); + pwmWriteServo(1, servo[5]); + break; + + case MULTITYPE_TRI: + pwmWriteServo(0, servo[5]); + break; + + case MULTITYPE_AIRPLANE: + + break; + + case MULTITYPE_FLYING_WING: + case MULTITYPE_GIMBAL: + pwmWriteServo(0, servo[0]); + pwmWriteServo(1, servo[1]); + break; + + default: + // Two servos for SERVO_TILT, if enabled + if (feature(FEATURE_SERVO_TILT)) { + pwmWriteServo(0, servo[0]); + pwmWriteServo(1, servo[1]); + } + break; + } +} + +extern uint8_t cliMode; + +void writeMotors(void) +{ + uint8_t i; + + for (i = 0; i < numberMotor; i++) + pwmWriteMotor(i, motor[i]); +} + +void writeAllMotors(int16_t mc) +{ + uint8_t i; + + // Sends commands to all motors + for (i = 0; i < numberMotor; i++) + motor[i] = mc; + writeMotors(); +} + +static void airplaneMixer(void) +{ +#if 0 + uint16_t servomid[8]; + int16_t flaperons[2] = { 0, 0 }; + + for (i = 0; i < 8; i++) { + servomid[i] = 1500 + cfg.servotrim[i]; // servo center is 1500? + } + + if (!f.ARMED) + motor[0] = cfg.mincommand; // Kill throttle when disarmed + else + motor[0] = rcData[THROTTLE]; + + if (cfg.flaperons) { + + + } + + if (cfg.flaps) { + int16_t flap = 1500 - constrain(rcData[cfg.flaps], cfg.servoendpoint_low[2], cfg.servoendpoint_high[2]); + static int16_t slowFlaps = flap; + + if (cfg.flapspeed) { + if (slowFlaps < flap) { + slowFlaps += cfg.flapspeed; + } else if (slowFlaps > flap) { + slowFlaps -= cfg.flapspeed; + } + } else { + slowFlaps = flap; + } + servo[2] = servomid[2] + (slowFlaps * cfg.servoreverse[2]); + } + + if (f.PASSTHRU_MODE) { // Direct passthru from RX + servo[3] = servomid[3] + ((rcCommand[ROLL] + flapperons[0]) * cfg.servoreverse[3]); // Wing 1 + servo[4] = servomid[4] + ((rcCommand[ROLL] + flapperons[1]) * cfg.servoreverse[4]); // Wing 2 + servo[5] = servomid[5] + (rcCommand[YAW] * cfg.servoreverse[5]); // Rudder + servo[6] = servomid[6] + (rcCommand[PITCH] * cfg.servoreverse[6]); // Elevator + } else { // Assisted modes (gyro only or gyro+acc according to AUX configuration in Gui + servo[3] = (servomid[3] + ((axisPID[ROLL] + flapperons[0]) * cfg.servoreverse[3])); // Wing 1 + servo[4] = (servomid[4] + ((axisPID[ROLL] + flapperons[1]) * cfg.servoreverse[4])); // Wing 2 + servo[5] = (servomid[5] + (axisPID[YAW] * cfg.servoreverse[5])); // Rudder + servo[6] = (servomid[6] + (axisPID[PITCH] * cfg.servoreverse[6])); // Elevator + } +#endif +} + +void mixTable(void) +{ + int16_t maxMotor; + uint32_t i; + + if (numberMotor > 3) { + // prevent "yaw jump" during yaw correction + axisPID[YAW] = constrain(axisPID[YAW], -100 - abs(rcCommand[YAW]), +100 + abs(rcCommand[YAW])); + } + + // motors for non-servo mixes + if (numberMotor > 1) + for (i = 0; i < numberMotor; i++) + motor[i] = rcCommand[THROTTLE] * currentMixer[i].throttle + axisPID[PITCH] * currentMixer[i].pitch + axisPID[ROLL] * currentMixer[i].roll + cfg.yaw_direction * axisPID[YAW] * currentMixer[i].yaw; + + // airplane / servo mixes + switch (cfg.mixerConfiguration) { + case MULTITYPE_BI: + servo[4] = constrain(1500 + (cfg.yaw_direction * axisPID[YAW]) + axisPID[PITCH], 1020, 2000); //LEFT + servo[5] = constrain(1500 + (cfg.yaw_direction * axisPID[YAW]) - axisPID[PITCH], 1020, 2000); //RIGHT + break; + + case MULTITYPE_TRI: + servo[5] = constrain(cfg.tri_yaw_middle + cfg.yaw_direction * axisPID[YAW], cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR + break; + + case MULTITYPE_GIMBAL: + servo[0] = constrain(cfg.gimbal_pitch_mid + cfg.gimbal_pitch_gain * angle[PITCH] / 16 + rcCommand[PITCH], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max); + servo[1] = constrain(cfg.gimbal_roll_mid + cfg.gimbal_roll_gain * angle[ROLL] / 16 + rcCommand[ROLL], cfg.gimbal_roll_min, cfg.gimbal_roll_max); + break; + + case MULTITYPE_AIRPLANE: + airplaneMixer(); + break; + + case MULTITYPE_FLYING_WING: + motor[0] = rcCommand[THROTTLE]; + if (f.PASSTHRU_MODE) { + // do not use sensors for correction, simple 2 channel mixing + servo[0] = cfg.pitch_direction_l * (rcData[PITCH] - cfg.midrc) + cfg.roll_direction_l * (rcData[ROLL] - cfg.midrc); + servo[1] = cfg.pitch_direction_r * (rcData[PITCH] - cfg.midrc) + cfg.roll_direction_r * (rcData[ROLL] - cfg.midrc); + } else { + // use sensors to correct (gyro only or gyro + acc) + servo[0] = cfg.pitch_direction_l * axisPID[PITCH] + cfg.roll_direction_l * axisPID[ROLL]; + servo[1] = cfg.pitch_direction_r * axisPID[PITCH] + cfg.roll_direction_r * axisPID[ROLL]; + } + servo[0] = constrain(servo[0] + cfg.wing_left_mid, cfg.wing_left_min, cfg.wing_left_max); + servo[1] = constrain(servo[1] + cfg.wing_right_mid, cfg.wing_right_min, cfg.wing_right_max); + break; + } + + // do camstab + if (feature(FEATURE_SERVO_TILT)) { + uint16_t aux[2] = { 0, 0 }; + + if ((cfg.gimbal_flags & GIMBAL_NORMAL) || (cfg.gimbal_flags & GIMBAL_TILTONLY)) + aux[0] = rcData[AUX3] - cfg.midrc; + if (!(cfg.gimbal_flags & GIMBAL_DISABLEAUX34)) + aux[1] = rcData[AUX4] - cfg.midrc; + + servo[0] = cfg.gimbal_pitch_mid + aux[0]; + servo[1] = cfg.gimbal_roll_mid + aux[1]; + + if (rcOptions[BOXCAMSTAB]) { + if (cfg.gimbal_flags & GIMBAL_MIXTILT) { + servo[0] = (-cfg.gimbal_roll_gain) * angle[PITCH] / 16 - cfg.gimbal_roll_gain * angle[ROLL] / 16; + servo[1] = (-cfg.gimbal_roll_gain) * angle[PITCH] / 16 - cfg.gimbal_roll_gain * angle[ROLL] / 16; + } else { + servo[0] += cfg.gimbal_pitch_gain * angle[PITCH] / 16; + servo[1] += cfg.gimbal_roll_gain * angle[ROLL] / 16; + } + } + + servo[0] = constrain(servo[0], cfg.gimbal_pitch_min, cfg.gimbal_pitch_max); + servo[1] = constrain(servo[1], cfg.gimbal_roll_min, cfg.gimbal_roll_max); + } + + if (cfg.gimbal_flags & GIMBAL_FORWARDAUX) { + int offset = 0; + if (feature(FEATURE_SERVO_TILT)) + offset = 2; + for (i = 0; i < 4; i++) + pwmWriteServo(i + offset, rcData[AUX1 + i]); + } + + maxMotor = motor[0]; + for (i = 1; i < numberMotor; i++) + if (motor[i] > maxMotor) + maxMotor = motor[i]; + for (i = 0; i < numberMotor; i++) { + if (maxMotor > cfg.maxthrottle) // this is a way to still have good gyro corrections if at least one motor reaches its max. + motor[i] -= maxMotor - cfg.maxthrottle; + motor[i] = constrain(motor[i], cfg.minthrottle, cfg.maxthrottle); + if ((rcData[THROTTLE]) < cfg.mincheck) { + if (!feature(FEATURE_MOTOR_STOP)) + motor[i] = cfg.minthrottle; + else + motor[i] = cfg.mincommand; + } + if (!f.ARMED) + motor[i] = cfg.mincommand; + } +} diff --git a/src/baseflight/src/mw.c b/src/baseflight/src/mw.c new file mode 100755 index 0000000000..7330e24909 --- /dev/null +++ b/src/baseflight/src/mw.c @@ -0,0 +1,648 @@ +#include "board.h" +#include "mw.h" + +// October 2012 V2.1-dev + +flags_t f; +int16_t debug[4]; +uint8_t toggleBeep = 0; +uint32_t currentTime = 0; +uint32_t previousTime = 0; +uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop +int16_t headFreeModeHold; + +int16_t annex650_overrun_count = 0; +uint8_t vbat; // battery voltage in 0.1V steps +int16_t telemTemperature1; // gyro sensor temperature + +int16_t failsafeCnt = 0; +int16_t failsafeEvents = 0; +int16_t rcData[8] = { 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502 }; // interval [1000;2000] +int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW +int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL +int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE +rcReadRawDataPtr rcReadRawFunc = NULL; // receive data from default (pwm/ppm) or additional (spek/sbus/?? receiver drivers) + +uint8_t dynP8[3], dynI8[3], dynD8[3]; +uint8_t rcOptions[CHECKBOXITEMS]; + +int16_t axisPID[3]; + +// ********************** +// GPS +// ********************** +int32_t GPS_coord[2]; +int32_t GPS_home[2]; +int32_t GPS_hold[2]; +uint8_t GPS_numSat; +uint16_t GPS_distanceToHome; // distance to home point in meters +int16_t GPS_directionToHome; // direction to home or hol point in degrees +uint16_t GPS_altitude, GPS_speed; // altitude in 0.1m and speed in 0.1m/s +uint8_t GPS_update = 0; // it's a binary toogle to distinct a GPS position update +int16_t GPS_angle[2] = { 0, 0 }; // it's the angles that must be applied for GPS correction +uint16_t GPS_ground_course = 0; // degrees * 10 +uint8_t GPS_Present = 0; // Checksum from Gps serial +uint8_t GPS_Enable = 0; +int16_t nav[2]; +int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother +int8_t nav_mode = NAV_MODE_NONE; // Navigation mode + +// Automatic ACC Offset Calibration +uint16_t InflightcalibratingA = 0; +int16_t AccInflightCalibrationArmed; +uint16_t AccInflightCalibrationMeasurementDone = 0; +uint16_t AccInflightCalibrationSavetoEEProm = 0; +uint16_t AccInflightCalibrationActive = 0; + +// Battery monitoring stuff +uint8_t batteryCellCount = 3; // cell count +uint16_t batteryWarningVoltage; // annoying buzzer after this one, battery ready to be dead + +void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat) +{ + uint8_t i, r; + + for (r = 0; r < repeat; r++) { + for (i = 0; i < num; i++) { + LED0_TOGGLE; // switch LEDPIN state + BEEP_ON; + delay(wait); + BEEP_OFF; + } + delay(60); + } +} + +#define BREAKPOINT 1500 + +// this code is executed at each loop and won't interfere with control loop if it lasts less than 650 microseconds +void annexCode(void) +{ + static uint32_t calibratedAccTime; + uint16_t tmp, tmp2; + static uint8_t buzzerFreq; //delay between buzzer ring + static uint8_t vbatTimer = 0; + uint8_t axis, prop1, prop2; + static uint8_t ind = 0; + uint16_t vbatRaw = 0; + static uint16_t vbatRawArray[8]; + uint8_t i; + + // PITCH & ROLL only dynamic PID adjustemnt, depending on throttle value + if (rcData[THROTTLE] < BREAKPOINT) { + prop2 = 100; + } else { + if (rcData[THROTTLE] < 2000) { + prop2 = 100 - (uint16_t) cfg.dynThrPID * (rcData[THROTTLE] - BREAKPOINT) / (2000 - BREAKPOINT); + } else { + prop2 = 100 - cfg.dynThrPID; + } + } + + for (axis = 0; axis < 3; axis++) { + tmp = min(abs(rcData[axis] - cfg.midrc), 500); + if (axis != 2) { // ROLL & PITCH + if (cfg.deadband) { + if (tmp > cfg.deadband) { + tmp -= cfg.deadband; + } else { + tmp = 0; + } + } + + tmp2 = tmp / 100; + rcCommand[axis] = lookupPitchRollRC[tmp2] + (tmp - tmp2 * 100) * (lookupPitchRollRC[tmp2 + 1] - lookupPitchRollRC[tmp2]) / 100; + prop1 = 100 - (uint16_t) cfg.rollPitchRate * tmp / 500; + prop1 = (uint16_t) prop1 *prop2 / 100; + } else { // YAW + if (cfg.yawdeadband) { + if (tmp > cfg.yawdeadband) { + tmp -= cfg.yawdeadband; + } else { + tmp = 0; + } + } + rcCommand[axis] = tmp; + prop1 = 100 - (uint16_t) cfg.yawRate * tmp / 500; + } + dynP8[axis] = (uint16_t) cfg.P8[axis] * prop1 / 100; + dynD8[axis] = (uint16_t) cfg.D8[axis] * prop1 / 100; + if (rcData[axis] < cfg.midrc) + rcCommand[axis] = -rcCommand[axis]; + } + + tmp = constrain(rcData[THROTTLE], cfg.mincheck, 2000); + tmp = (uint32_t) (tmp - cfg.mincheck) * 1000 / (2000 - cfg.mincheck); // [MINCHECK;2000] -> [0;1000] + tmp2 = tmp / 100; + rcCommand[THROTTLE] = lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100; // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE] + + if(f.HEADFREE_MODE) { + float radDiff = (heading - headFreeModeHold) * M_PI / 180.0f; + float cosDiff = cosf(radDiff); + float sinDiff = sinf(radDiff); + int16_t rcCommand_PITCH = rcCommand[PITCH] * cosDiff + rcCommand[ROLL] * sinDiff; + rcCommand[ROLL] = rcCommand[ROLL] * cosDiff - rcCommand[PITCH] * sinDiff; + rcCommand[PITCH] = rcCommand_PITCH; + } + + if (feature(FEATURE_VBAT)) { + if (!(++vbatTimer % VBATFREQ)) { + vbatRawArray[(ind++) % 8] = adcGetChannel(ADC_BATTERY); + for (i = 0; i < 8; i++) + vbatRaw += vbatRawArray[i]; + vbat = batteryAdcToVoltage(vbatRaw / 8); + } + if ((vbat > batteryWarningVoltage) || (vbat < cfg.vbatmincellvoltage)) { // VBAT ok, buzzer off + buzzerFreq = 0; + } else + buzzerFreq = 4; // low battery + } + + buzzer(buzzerFreq); // external buzzer routine that handles buzzer events globally now + + if ((calibratingA > 0 && sensors(SENSOR_ACC)) || (calibratingG > 0)) { // Calibration phasis + LED0_TOGGLE; + } else { + if (f.ACC_CALIBRATED) + LED0_OFF; + if (f.ARMED) + LED0_ON; + // This will switch to/from 9600 or 115200 baud depending on state. Of course, it should only do it on changes. + if (feature(FEATURE_TELEMETRY)) + initTelemetry(f.ARMED); + } + +#ifdef LEDRING + if (feature(FEATURE_LED_RING)) { + static uint32_t LEDTime; + if ((int32_t)(currentTime - LEDTime) >= 0) { + LEDTime = currentTime + 50000; + ledringState(); + } + } +#endif + + if ((int32_t)(currentTime - calibratedAccTime) >= 0) { + if (!f.SMALL_ANGLES_25) { + f.ACC_CALIBRATED = 0; // the multi uses ACC and is not calibrated or is too much inclinated + LED0_TOGGLE; + calibratedAccTime = currentTime + 500000; + } else { + f.ACC_CALIBRATED = 1; + } + } + + serialCom(); + + if (sensors(SENSOR_GPS)) { + static uint32_t GPSLEDTime; + if ((int32_t)(currentTime - GPSLEDTime) >= 0 && (GPS_numSat >= 5)) { + GPSLEDTime = currentTime + 150000; + LED1_TOGGLE; + } + } + + // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. + if (gyro.temperature) + gyro.temperature(&telemTemperature1); + else { + // TODO MCU temp + } +} + +uint16_t pwmReadRawRC(uint8_t chan) +{ + uint16_t data; + + data = pwmRead(cfg.rcmap[chan]); + if (data < 750 || data > 2250) + data = cfg.midrc; + + return data; +} + +void computeRC(void) +{ + static int16_t rcData4Values[8][4], rcDataMean[8]; + static uint8_t rc4ValuesIndex = 0; + uint8_t chan, a; + + rc4ValuesIndex++; + for (chan = 0; chan < 8; chan++) { + rcData4Values[chan][rc4ValuesIndex % 4] = rcReadRawFunc(chan); + rcDataMean[chan] = 0; + for (a = 0; a < 4; a++) + rcDataMean[chan] += rcData4Values[chan][a]; + + rcDataMean[chan] = (rcDataMean[chan] + 2) / 4; + if (rcDataMean[chan] < rcData[chan] - 3) + rcData[chan] = rcDataMean[chan] + 2; + if (rcDataMean[chan] > rcData[chan] + 3) + rcData[chan] = rcDataMean[chan] - 2; + } +} + +void loop(void) +{ + static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors + uint8_t axis, i; + int16_t error, errorAngle; + int16_t delta, deltaSum; + int16_t PTerm, ITerm, PTermACC, ITermACC = 0, PTermGYRO = 0, ITermGYRO = 0, DTerm; + static int16_t lastGyro[3] = { 0, 0, 0 }; + static int16_t delta1[3], delta2[3]; + static int16_t errorGyroI[3] = { 0, 0, 0 }; + static int16_t errorAngleI[2] = { 0, 0 }; + static uint32_t rcTime = 0; + static int16_t initialThrottleHold; + static uint32_t loopTime; + uint16_t auxState = 0; + int16_t prop; + + // this will return false if spektrum is disabled. shrug. + if (spektrumFrameComplete()) + computeRC(); + + if ((int32_t)(currentTime - rcTime) >= 0) { // 50Hz + rcTime = currentTime + 20000; + // TODO clean this up. computeRC should handle this check + if (!feature(FEATURE_SPEKTRUM)) + computeRC(); + + // Failsafe routine + if (feature(FEATURE_FAILSAFE)) { + if (failsafeCnt > (5 * cfg.failsafe_delay) && f.ARMED) { // Stabilize, and set Throttle to specified level + for (i = 0; i < 3; i++) + rcData[i] = cfg.midrc; // after specified guard time after RC signal is lost (in 0.1sec) + rcData[THROTTLE] = cfg.failsafe_throttle; + if (failsafeCnt > 5 * (cfg.failsafe_delay + cfg.failsafe_off_delay)) { // Turn OFF motors after specified Time (in 0.1sec) + f.ARMED = 0; // This will prevent the copter to automatically rearm if failsafe shuts it down and prevents + f.OK_TO_ARM = 0; // to restart accidentely by just reconnect to the tx - you will have to switch off first to rearm + } + failsafeEvents++; + } + if (failsafeCnt > (5 * cfg.failsafe_delay) && !f.ARMED) { // Turn off "Ok To arm to prevent the motors from spinning after repowering the RX with low throttle and aux to arm + f.ARMED = 0; // This will prevent the copter to automatically rearm if failsafe shuts it down and prevents + f.OK_TO_ARM = 0; // to restart accidentely by just reconnect to the tx - you will have to switch off first to rearm + } + failsafeCnt++; + } + + if (rcData[THROTTLE] < cfg.mincheck) { + errorGyroI[ROLL] = 0; + errorGyroI[PITCH] = 0; + errorGyroI[YAW] = 0; + errorAngleI[ROLL] = 0; + errorAngleI[PITCH] = 0; + rcDelayCommand++; + if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck && !f.ARMED) { + if (rcDelayCommand == 20) { + calibratingG = 1000; + if (feature(FEATURE_GPS)) + GPS_reset_home_position(); + } + } else if (feature(FEATURE_INFLIGHT_ACC_CAL) && (!f.ARMED && rcData[YAW] < cfg.mincheck && rcData[PITCH] > cfg.maxcheck && rcData[ROLL] > cfg.maxcheck)) { + if (rcDelayCommand == 20) { + if (AccInflightCalibrationMeasurementDone) { // trigger saving into eeprom after landing + AccInflightCalibrationMeasurementDone = 0; + AccInflightCalibrationSavetoEEProm = 1; + } else { + AccInflightCalibrationArmed = !AccInflightCalibrationArmed; + if (AccInflightCalibrationArmed) { + toggleBeep = 2; + } else { + toggleBeep = 3; + } + } + } + } else if (cfg.activate[BOXARM] > 0) { + if (rcOptions[BOXARM] && f.OK_TO_ARM) { + // TODO: feature(FEATURE_FAILSAFE) && failsafeCnt == 0 + f.ARMED = 1; + headFreeModeHold = heading; + } else if (f.ARMED) + f.ARMED = 0; + rcDelayCommand = 0; + } else if ((rcData[YAW] < cfg.mincheck || (cfg.retarded_arm == 1 && rcData[ROLL] < cfg.mincheck)) && f.ARMED) { + if (rcDelayCommand == 20) + f.ARMED = 0; // rcDelayCommand = 20 => 20x20ms = 0.4s = time to wait for a specific RC command to be acknowledged + } else if ((rcData[YAW] > cfg.maxcheck || (rcData[ROLL] > cfg.maxcheck && cfg.retarded_arm == 1)) && rcData[PITCH] < cfg.maxcheck && !f.ARMED && calibratingG == 0 && f.ACC_CALIBRATED) { + if (rcDelayCommand == 20) { + f.ARMED = 1; + headFreeModeHold = heading; + } + } else + rcDelayCommand = 0; + } else if (rcData[THROTTLE] > cfg.maxcheck && !f.ARMED) { + if (rcData[YAW] < cfg.mincheck && rcData[PITCH] < cfg.mincheck) { // throttle=max, yaw=left, pitch=min + if (rcDelayCommand == 20) + calibratingA = 400; + rcDelayCommand++; + } else if (rcData[YAW] > cfg.maxcheck && rcData[PITCH] < cfg.mincheck) { // throttle=max, yaw=right, pitch=min + if (rcDelayCommand == 20) + f.CALIBRATE_MAG = 1; // MAG calibration request + rcDelayCommand++; + } else if (rcData[PITCH] > cfg.maxcheck) { + cfg.angleTrim[PITCH] += 2; + writeParams(1); +#ifdef LEDRING + if (feature(FEATURE_LED_RING)) + ledringBlink(); +#endif + } else if (rcData[PITCH] < cfg.mincheck) { + cfg.angleTrim[PITCH] -= 2; + writeParams(1); +#ifdef LEDRING + if (feature(FEATURE_LED_RING)) + ledringBlink(); +#endif + } else if (rcData[ROLL] > cfg.maxcheck) { + cfg.angleTrim[ROLL] += 2; + writeParams(1); +#ifdef LEDRING + if (feature(FEATURE_LED_RING)) + ledringBlink(); +#endif + } else if (rcData[ROLL] < cfg.mincheck) { + cfg.angleTrim[ROLL] -= 2; + writeParams(1); +#ifdef LEDRING + if (feature(FEATURE_LED_RING)) + ledringBlink(); +#endif + } else { + rcDelayCommand = 0; + } + } + + if (feature(FEATURE_INFLIGHT_ACC_CAL)) { + if (AccInflightCalibrationArmed && f.ARMED && rcData[THROTTLE] > cfg.mincheck && !rcOptions[BOXARM]) { // Copter is airborne and you are turning it off via boxarm : start measurement + InflightcalibratingA = 50; + AccInflightCalibrationArmed = 0; + } + if (rcOptions[BOXPASSTHRU]) { // Use the Passthru Option to activate : Passthru = TRUE Meausrement started, Land and passtrhu = 0 measurement stored + if (!AccInflightCalibrationActive && !AccInflightCalibrationMeasurementDone) + InflightcalibratingA = 50; + } else if (AccInflightCalibrationMeasurementDone && !f.ARMED) { + AccInflightCalibrationMeasurementDone = 0; + AccInflightCalibrationSavetoEEProm = 1; + } + } + + for (i = 0; i < 4; i++) + auxState |= (rcData[AUX1 + i] < 1300) << (3 * i) | (1300 < rcData[AUX1 + i] && rcData[AUX1 + i] < 1700) << (3 * i + 1) | (rcData[AUX1 + i] > 1700) << (3 * i + 2); + for (i = 0; i < CHECKBOXITEMS; i++) + rcOptions[i] = (auxState & cfg.activate[i]) > 0; + + // note: if FAILSAFE is disable, failsafeCnt > 5*FAILSAVE_DELAY is always false + if ((rcOptions[BOXANGLE] || (failsafeCnt > 5 * cfg.failsafe_delay)) && (sensors(SENSOR_ACC))) { + // bumpless transfer to Level mode + if (!f.ANGLE_MODE) { + errorAngleI[ROLL] = 0; + errorAngleI[PITCH] = 0; + f.ANGLE_MODE = 1; + } + } else { + f.ANGLE_MODE = 0; // failsave support + } + + if (rcOptions[BOXHORIZON]) { + if (!f.HORIZON_MODE) { + errorAngleI[ROLL] = 0; + errorAngleI[PITCH] = 0; + f.HORIZON_MODE = 1; + } + } else { + f.HORIZON_MODE = 0; + } + + if ((rcOptions[BOXARM]) == 0) + f.OK_TO_ARM = 1; + if (f.ANGLE_MODE || f.HORIZON_MODE) { + LED1_ON; + } else { + LED1_OFF; + } + +#ifdef BARO + if (sensors(SENSOR_BARO)) { + if (rcOptions[BOXBARO]) { + if (!f.BARO_MODE) { + f.BARO_MODE = 1; + AltHold = EstAlt; + initialThrottleHold = rcCommand[THROTTLE]; + errorAltitudeI = 0; + BaroPID = 0; + } + } else + f.BARO_MODE = 0; + } +#endif + +#ifdef MAG + if (sensors(SENSOR_MAG)) { + if (rcOptions[BOXMAG]) { + if (!f.MAG_MODE) { + f.MAG_MODE = 1; + magHold = heading; + } + } else + f.MAG_MODE = 0; + if (rcOptions[BOXHEADFREE]) { + if (!f.HEADFREE_MODE) { + f.HEADFREE_MODE = 1; + } + } else { + f.HEADFREE_MODE = 0; + } + if (rcOptions[BOXHEADADJ]) { + headFreeModeHold = heading; // acquire new heading + } + } +#endif + + if (sensors(SENSOR_GPS)) { + if (f.GPS_FIX && GPS_numSat >= 5) { + if (rcOptions[BOXGPSHOME]) { + if (!f.GPS_HOME_MODE) { + f.GPS_HOME_MODE = 1; + GPS_set_next_wp(&GPS_home[LAT], &GPS_home[LON]); + nav_mode = NAV_MODE_WP; + } + } else { + f.GPS_HOME_MODE = 0; + } + if (rcOptions[BOXGPSHOLD]) { + if (!f.GPS_HOLD_MODE) { + f.GPS_HOLD_MODE = 1; + GPS_hold[LAT] = GPS_coord[LAT]; + GPS_hold[LON] = GPS_coord[LON]; + GPS_set_next_wp(&GPS_hold[LAT], &GPS_hold[LON]); + nav_mode = NAV_MODE_POSHOLD; + } + } else { + f.GPS_HOLD_MODE = 0; + } + } + } + + if (rcOptions[BOXPASSTHRU]) { + f.PASSTHRU_MODE = 1; + } else { + f.PASSTHRU_MODE = 0; + } + + if (cfg.mixerConfiguration == MULTITYPE_FLYING_WING || cfg.mixerConfiguration == MULTITYPE_AIRPLANE) { + f.HEADFREE_MODE = 0; + } + } else { // not in rc loop + static int8_t taskOrder = 0; // never call all function in the same loop, to avoid high delay spikes + switch (taskOrder++ % 4) { + case 0: +#ifdef MAG + if (sensors(SENSOR_MAG)) + Mag_getADC(); +#endif + break; + case 1: +#ifdef BARO + if (sensors(SENSOR_BARO)) + Baro_update(); +#endif + break; + case 2: +#ifdef BARO + if (sensors(SENSOR_BARO)) + getEstimatedAltitude(); +#endif + break; + case 3: +#ifdef SONAR + if (sensors(SENSOR_SONAR)) { + Sonar_update(); + debug[2] = sonarAlt; + } +#endif + break; + default: + taskOrder = 0; + break; + } + } + + currentTime = micros(); + if (cfg.looptime == 0 || (int32_t)(currentTime - loopTime) >= 0) { + loopTime = currentTime + cfg.looptime; + + computeIMU(); + // Measure loop rate just afer reading the sensors + currentTime = micros(); + cycleTime = (int32_t)(currentTime - previousTime); + previousTime = currentTime; +#ifdef MPU6050_DMP + mpu6050DmpLoop(); +#endif + +#ifdef MAG + if (sensors(SENSOR_MAG)) { + if (abs(rcCommand[YAW]) < 70 && f.MAG_MODE) { + int16_t dif = heading - magHold; + if (dif <= -180) + dif += 360; + if (dif >= +180) + dif -= 360; + if (f.SMALL_ANGLES_25) + rcCommand[YAW] -= dif * cfg.P8[PIDMAG] / 30; // 18 deg + } else + magHold = heading; + } +#endif + +#ifdef BARO + if (sensors(SENSOR_BARO)) { + if (f.BARO_MODE) { + if (abs(rcCommand[THROTTLE] - initialThrottleHold) > cfg.alt_hold_throttle_neutral) { + f.BARO_MODE = 0; // so that a new althold reference is defined + } + rcCommand[THROTTLE] = initialThrottleHold + BaroPID; + } + } +#endif + + if (sensors(SENSOR_GPS)) { + // Check that we really need to navigate ? + if ((!f.GPS_HOME_MODE && !f.GPS_HOLD_MODE) || !f.GPS_FIX_HOME) { + // If not. Reset nav loops and all nav related parameters + GPS_reset_nav(); + } else { + float sin_yaw_y = sinf(heading * 0.0174532925f); + float cos_yaw_x = cosf(heading * 0.0174532925f); + if (cfg.nav_slew_rate) { + nav_rated[LON] += constrain(wrap_18000(nav[LON] - nav_rated[LON]), -cfg.nav_slew_rate, cfg.nav_slew_rate); // TODO check this on uint8 + nav_rated[LAT] += constrain(wrap_18000(nav[LAT] - nav_rated[LAT]), -cfg.nav_slew_rate, cfg.nav_slew_rate); + GPS_angle[ROLL] = (nav_rated[LON] * cos_yaw_x - nav_rated[LAT] * sin_yaw_y) / 10; + GPS_angle[PITCH] = (nav_rated[LON] * sin_yaw_y + nav_rated[LAT] * cos_yaw_x) / 10; + } else { + GPS_angle[ROLL] = (nav[LON] * cos_yaw_x - nav[LAT] * sin_yaw_y) / 10; + GPS_angle[PITCH] = (nav[LON] * sin_yaw_y + nav[LAT] * cos_yaw_x) / 10; + } + } + } + + // **** PITCH & ROLL & YAW PID **** + prop = max(abs(rcCommand[PITCH]), abs(rcCommand[ROLL])); // range [0;500] + for (axis = 0; axis < 3; axis++) { + if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2) { // MODE relying on ACC + // 50 degrees max inclination + errorAngle = constrain(2 * rcCommand[axis] + GPS_angle[axis], -500, +500) - angle[axis] + cfg.angleTrim[axis]; +#ifdef LEVEL_PDF + PTermACC = -(int32_t)angle[axis] * cfg.P8[PIDLEVEL] / 100; +#else + PTermACC = (int32_t)errorAngle * cfg.P8[PIDLEVEL] / 100; // 32 bits is needed for calculation: errorAngle*P8[PIDLEVEL] could exceed 32768 16 bits is ok for result +#endif + PTermACC = constrain(PTermACC, -cfg.D8[PIDLEVEL] * 5, +cfg.D8[PIDLEVEL] * 5); + + errorAngleI[axis] = constrain(errorAngleI[axis] + errorAngle, -10000, +10000); // WindUp + ITermACC = ((int32_t)errorAngleI[axis] * cfg.I8[PIDLEVEL]) >> 12; + } + if (!f.ANGLE_MODE || axis == 2) { // MODE relying on GYRO or YAW axis + error = (int32_t)rcCommand[axis] * 10 * 8 / cfg.P8[axis]; + error -= gyroData[axis]; + + PTermGYRO = rcCommand[axis]; + + errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp + if (abs(gyroData[axis]) > 640) + errorGyroI[axis] = 0; + ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) >> 6; + } + if (f.HORIZON_MODE && axis < 2) { + PTerm = ((int32_t)PTermACC * (500 - prop) + (int32_t)PTermGYRO * prop) / 500; + ITerm = ((int32_t)ITermACC * (500 - prop) + (int32_t)ITermGYRO * prop) / 500; + } else { + if (f.ANGLE_MODE && axis < 2) { + PTerm = PTermACC; + ITerm = ITermACC; + } else { + PTerm = PTermGYRO; + ITerm = ITermGYRO; + } + } + + PTerm -= (int32_t)gyroData[axis] * dynP8[axis] / 10 / 8; // 32 bits is needed for calculation + + delta = gyroData[axis] - lastGyro[axis]; // 16 bits is ok here, the dif between 2 consecutive gyro reads is limited to 800 + lastGyro[axis] = gyroData[axis]; + deltaSum = delta1[axis] + delta2[axis] + delta; + delta2[axis] = delta1[axis]; + delta1[axis] = delta; + + DTerm = ((int32_t)deltaSum * dynD8[axis]) >> 5; // 32 bits is needed for calculation + axisPID[axis] = PTerm + ITerm - DTerm; + } + + mixTable(); + writeServos(); + writeMotors(); + } +} diff --git a/src/baseflight/src/mw.h b/src/baseflight/src/mw.h new file mode 100755 index 0000000000..2f47a83b5d --- /dev/null +++ b/src/baseflight/src/mw.h @@ -0,0 +1,387 @@ +#pragma once + +/* for VBAT monitoring frequency */ +#define VBATFREQ 6 // to read battery voltage - nth number of loop iterations +#define BARO_TAB_SIZE_MAX 48 + +#define VERSION 211 + +#define LAT 0 +#define LON 1 + +// Serial GPS only variables +// navigation mode +typedef enum NavigationMode +{ + NAV_MODE_NONE = 0, + NAV_MODE_POSHOLD, + NAV_MODE_WP +} NavigationMode; + +// Syncronized with GUI. Only exception is mixer > 11, which is always returned as 11 during serialization. +typedef enum MultiType +{ + MULTITYPE_TRI = 1, + MULTITYPE_QUADP = 2, + MULTITYPE_QUADX = 3, + MULTITYPE_BI = 4, + MULTITYPE_GIMBAL = 5, + MULTITYPE_Y6 = 6, + MULTITYPE_HEX6 = 7, + MULTITYPE_FLYING_WING = 8, + MULTITYPE_Y4 = 9, + MULTITYPE_HEX6X = 10, + MULTITYPE_OCTOX8 = 11, // Java GUI is same for the next 3 configs + MULTITYPE_OCTOFLATP = 12, // MultiWinGui shows this differently + MULTITYPE_OCTOFLATX = 13, // MultiWinGui shows this differently + MULTITYPE_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported) + MULTITYPE_HELI_120_CCPM = 15, + MULTITYPE_HELI_90_DEG = 16, + MULTITYPE_VTAIL4 = 17, + MULTITYPE_CUSTOM = 18, // no current GUI displays this + MULTITYPE_LAST = 19 +} MultiType; + +typedef enum GimbalFlags { + GIMBAL_NORMAL = 1 << 0, + GIMBAL_TILTONLY = 1 << 1, + GIMBAL_DISABLEAUX34 = 1 << 2, + GIMBAL_FORWARDAUX = 1 << 3, + GIMBAL_MIXTILT = 1 << 4, +} GimbalFlags; + +/*********** RC alias *****************/ +enum { + ROLL = 0, + PITCH, + YAW, + THROTTLE, + AUX1, + AUX2, + AUX3, + AUX4 +}; + +enum { + PIDROLL, + PIDPITCH, + PIDYAW, + PIDALT, + PIDPOS, + PIDPOSR, + PIDNAVR, + PIDLEVEL, + PIDMAG, + PIDVEL, + PIDITEMS +}; + +enum { + BOXANGLE = 0, + BOXHORIZON, + BOXBARO, + BOXMAG, + BOXCAMSTAB, + BOXCAMTRIG, + BOXARM, + BOXGPSHOME, + BOXGPSHOLD, + BOXPASSTHRU, + BOXHEADFREE, + BOXBEEPERON, + BOXLEDMAX, + BOXLLIGHTS, + BOXHEADADJ, + CHECKBOXITEMS +}; + +#define min(a, b) ((a) < (b) ? (a) : (b)) +#define max(a, b) ((a) > (b) ? (a) : (b)) +#define abs(x) ((x) > 0 ? (x) : -(x)) +#define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt))) + +typedef struct motorMixer_t { + float throttle; + float roll; + float pitch; + float yaw; +} motorMixer_t; + +typedef struct mixer_t { + uint8_t numberMotor; + uint8_t useServo; + const motorMixer_t *motor; +} mixer_t; + +enum { + ALIGN_GYRO = 0, + ALIGN_ACCEL = 1, + ALIGN_MAG = 2 +}; + +typedef struct config_t { + uint8_t version; + uint16_t size; + uint8_t magic_be; // magic number, should be 0xBE + uint8_t mixerConfiguration; + uint32_t enabledFeatures; + + uint16_t looptime; // imu loop time in us + + uint8_t P8[PIDITEMS]; + uint8_t I8[PIDITEMS]; + uint8_t D8[PIDITEMS]; + + uint8_t rcRate8; + uint8_t rcExpo8; + uint8_t thrMid8; + uint8_t thrExpo8; + + uint8_t rollPitchRate; + uint8_t yawRate; + + uint8_t dynThrPID; + int16_t accZero[3]; + int16_t magZero[3]; + int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/ + int16_t angleTrim[2]; // accelerometer trim + + // sensor-related stuff + int8_t align[3][3]; // acc, gyro, mag alignment (ex: with sensor output of X, Y, Z, align of 1 -3 2 would return X, -Z, Y) + uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device + uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter + uint8_t acc_lpf_for_velocity; // ACC lowpass for AccZ height hold + uint8_t accz_deadband; // ?? + uint16_t gyro_lpf; // mpuX050 LPF setting (TODO make it work on L3GD as well) + uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter. + uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively + uint8_t mpu6050_scale; // seems es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. fucking invenshit won't release chip IDs so I can't autodetect it. + uint8_t baro_tab_size; // size of baro filter array + float baro_noise_lpf; // additional LPF to reduce baro noise + float baro_cf; // apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity) + uint8_t moron_threshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. + + uint16_t activate[CHECKBOXITEMS]; // activate switches + uint8_t vbatscale; // adjust this to match battery voltage to reported value + uint8_t vbatmaxcellvoltage; // maximum voltage per cell, used for auto-detecting battery voltage in 0.1V units, default is 43 (4.3V) + uint8_t vbatmincellvoltage; // minimum voltage per cell, this triggers battery out alarms, in 0.1V units, default is 33 (3.3V) + uint8_t power_adc_channel; // which channel is used for current sensor. Right now, only 2 places are supported: RC_CH2 (unused when in CPPM mode, = 1), RC_CH8 (last channel in PWM mode, = 9) + + // Radio/ESC-related configuration + uint8_t rcmap[8]; // mapping of radio channels to internal RPYTA+ order + uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. + uint8_t yawdeadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero. + uint8_t alt_hold_throttle_neutral; // defines the neutral zone of throttle stick during altitude hold, default setting is +/-20 + uint8_t spektrum_hires; // spektrum high-resolution y/n (1024/2048bit) + uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here + uint16_t mincheck; // minimum rc end + uint16_t maxcheck; // maximum rc end + uint8_t retarded_arm; // allow disarsm/arm on throttle down + roll left/right + + // Failsafe related configuration + uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10) + uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200) + uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500. + + // motor/esc/servo related stuff + uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed. + uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 + uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs + uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) + uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) + int16_t servotrim[8]; // Adjust Servo MID Offset & Swash angles + int8_t servoreverse[8]; // Invert servos by setting -1 + + // mixer-related configuration + int8_t yaw_direction; + uint16_t tri_yaw_middle; // tail servo center pos. - use this for initial trim + uint16_t tri_yaw_min; // tail servo min + uint16_t tri_yaw_max; // tail servo max + + // flying wing related configuration + uint16_t wing_left_min; // min/mid/max servo travel + uint16_t wing_left_mid; + uint16_t wing_left_max; + uint16_t wing_right_min; + uint16_t wing_right_mid; + uint16_t wing_right_max; + int8_t pitch_direction_l; // left servo - pitch orientation + int8_t pitch_direction_r; // right servo - pitch orientation (opposite sign to pitch_direction_l if servos are mounted mirrored) + int8_t roll_direction_l; // left servo - roll orientation + int8_t roll_direction_r; // right servo - roll orientation (same sign as ROLL_DIRECTION_L, if servos are mounted in mirrored orientation) + + // gimbal-related configuration + int8_t gimbal_pitch_gain; // gimbal pitch servo gain (tied to angle) can be negative to invert movement + int8_t gimbal_roll_gain; // gimbal roll servo gain (tied to angle) can be negative to invert movement + uint8_t gimbal_flags; // in servotilt mode, various things that affect stuff + uint16_t gimbal_pitch_min; // gimbal pitch servo min travel + uint16_t gimbal_pitch_max; // gimbal pitch servo max travel + uint16_t gimbal_pitch_mid; // gimbal pitch servo neutral value + uint16_t gimbal_roll_min; // gimbal roll servo min travel + uint16_t gimbal_roll_max; // gimbal roll servo max travel + uint16_t gimbal_roll_mid; // gimbal roll servo neutral value + + // gps-related stuff + uint8_t gps_type; // Type of GPS hardware. 0: NMEA 1: UBX 2+ ?? + uint32_t gps_baudrate; // GPS baudrate + uint16_t gps_wp_radius; // if we are within this distance to a waypoint then we consider it reached (distance is in cm) + uint8_t gps_lpf; // Low pass filter cut frequency for derivative calculation (default 20Hz) + uint8_t nav_slew_rate; // Adds a rate control to nav output, will smoothen out nav angle spikes + uint8_t nav_controls_heading; // copter faces toward the navigation point, maghold must be enabled for it + uint16_t nav_speed_min; // cm/sec + uint16_t nav_speed_max; // cm/sec + + // serial(uart1) baudrate + uint32_t serial_baudrate; + + motorMixer_t customMixer[MAX_MOTORS]; // custom mixtable + uint8_t magic_ef; // magic number, should be 0xEF + uint8_t chk; // XOR checksum +} config_t; + +typedef struct flags_t { + uint8_t OK_TO_ARM; + uint8_t ARMED; + uint8_t ACC_CALIBRATED; + uint8_t ANGLE_MODE; + uint8_t HORIZON_MODE; + uint8_t MAG_MODE; + uint8_t BARO_MODE; + uint8_t GPS_HOME_MODE; + uint8_t GPS_HOLD_MODE; + uint8_t HEADFREE_MODE; + uint8_t PASSTHRU_MODE; + uint8_t GPS_FIX; + uint8_t GPS_FIX_HOME; + uint8_t SMALL_ANGLES_25; + uint8_t CALIBRATE_MAG; +} flags_t; + +extern int16_t gyroZero[3]; +extern int16_t gyroData[3]; +extern int16_t angle[2]; +extern int16_t axisPID[3]; +extern int16_t rcCommand[4]; +extern uint8_t rcOptions[CHECKBOXITEMS]; +extern int16_t failsafeCnt; + +extern int16_t debug[4]; +extern int16_t gyroADC[3], accADC[3], accSmooth[3], magADC[3]; +extern uint16_t acc_1G; +extern uint32_t currentTime; +extern uint32_t previousTime; +extern uint16_t cycleTime; +extern uint16_t calibratingA; +extern uint16_t calibratingG; +extern int16_t heading; +extern int16_t annex650_overrun_count; +extern int32_t BaroAlt; +extern int16_t sonarAlt; +extern int32_t EstAlt; +extern int32_t AltHold; +extern int16_t errorAltitudeI; +extern int16_t BaroPID; +extern int16_t headFreeModeHold; +extern int16_t zVelocity; +extern int16_t heading, magHold; +extern int16_t motor[MAX_MOTORS]; +extern int16_t servo[8]; +extern int16_t rcData[8]; +extern uint8_t vbat; +extern int16_t telemTemperature1; // gyro sensor temperature +extern int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL +extern int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE +extern uint8_t toggleBeep; + +// GPS stuff +extern int32_t GPS_coord[2]; +extern int32_t GPS_home[2]; +extern int32_t GPS_hold[2]; +extern uint8_t GPS_numSat; +extern uint16_t GPS_distanceToHome; // distance to home or hold point in meters +extern int16_t GPS_directionToHome; // direction to home or hol point in degrees +extern uint16_t GPS_altitude,GPS_speed; // altitude in 0.1m and speed in 0.1m/s +extern uint8_t GPS_update; // it's a binary toogle to distinct a GPS position update +extern int16_t GPS_angle[2]; // it's the angles that must be applied for GPS correction +extern uint16_t GPS_ground_course; // degrees*10 +extern uint8_t GPS_Present; // Checksum from Gps serial +extern uint8_t GPS_Enable; +extern int16_t nav[2]; +extern int8_t nav_mode; // Navigation mode +extern int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother + +extern config_t cfg; +extern flags_t f; +extern sensor_t acc; +extern sensor_t gyro; +extern baro_t baro; + +// main +void loop(void); + +// IMU +void imuInit(void); +void annexCode(void); +void computeIMU(void); +void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat); +void getEstimatedAltitude(void); + +// Sensors +void sensorsAutodetect(void); +void batteryInit(void); +uint16_t batteryAdcToVoltage(uint16_t src); +void ACC_getADC(void); +void Baro_update(void); +void Gyro_getADC(void); +void Mag_init(void); +void Mag_getADC(void); +void Sonar_init(void); +void Sonar_update(void); + +// Output +void mixerInit(void); +void mixerLoadMix(int index); +void writeServos(void); +void writeMotors(void); +void writeAllMotors(int16_t mc); +void mixTable(void); + +// Serial +void serialInit(uint32_t baudrate); +void serialCom(void); + +// Config +void parseRcChannels(const char *input); +void readEEPROM(void); +void writeParams(uint8_t b); +void checkFirstTime(bool reset); +bool sensors(uint32_t mask); +void sensorsSet(uint32_t mask); +void sensorsClear(uint32_t mask); +uint32_t sensorsMask(void); +bool feature(uint32_t mask); +void featureSet(uint32_t mask); +void featureClear(uint32_t mask); +void featureClearAll(void); +uint32_t featureMask(void); + +// spektrum +void spektrumInit(void); +bool spektrumFrameComplete(void); + +// buzzer +void buzzer(uint8_t warn_vbat); + +// cli +void cliProcess(void); + +// gps +void gpsInit(uint32_t baudrate); +void GPS_reset_home_position(void); +void GPS_reset_nav(void); +void GPS_set_next_wp(int32_t* lat, int32_t* lon); +int32_t wrap_18000(int32_t error); + +// telemetry +void initTelemetry(bool State); +void sendTelemetry(void); diff --git a/src/baseflight/src/printf.c b/src/baseflight/src/printf.c new file mode 100644 index 0000000000..cefd9fcfa6 --- /dev/null +++ b/src/baseflight/src/printf.c @@ -0,0 +1,248 @@ +/* + * Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * Redistributions of source code must retain the above copyright notice, this list + * of conditions and the following disclaimer. + * + * Redistributions in binary form must reproduce the above copyright notice, this + * list of conditions and the following disclaimer in the documentation and/or other + * materials provided with the distribution. + * + * Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its + * contributors may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, + * INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT + * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, + * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY + * OF SUCH DAMAGE. + */ + +#include "board.h" +#include "printf.h" + +#define PRINTF_LONG_SUPPORT + +typedef void (*putcf) (void *, char); +static putcf stdout_putf; +static void *stdout_putp; + +#ifdef PRINTF_LONG_SUPPORT + +static void uli2a(unsigned long int num, unsigned int base, int uc, char *bf) +{ + int n = 0; + unsigned int d = 1; + while (num / d >= base) + d *= base; + while (d != 0) { + int dgt = num / d; + num %= d; + d /= base; + if (n || dgt > 0 || d == 0) { + *bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10); + ++n; + } + } + *bf = 0; +} + +static void li2a(long num, char *bf) +{ + if (num < 0) { + num = -num; + *bf++ = '-'; + } + uli2a(num, 10, 0, bf); +} + +#endif + +static void ui2a(unsigned int num, unsigned int base, int uc, char *bf) +{ + int n = 0; + unsigned int d = 1; + while (num / d >= base) + d *= base; + while (d != 0) { + int dgt = num / d; + num %= d; + d /= base; + if (n || dgt > 0 || d == 0) { + *bf++ = dgt + (dgt < 10 ? '0' : (uc ? 'A' : 'a') - 10); + ++n; + } + } + *bf = 0; +} + +static void i2a(int num, char *bf) +{ + if (num < 0) { + num = -num; + *bf++ = '-'; + } + ui2a(num, 10, 0, bf); +} + +static int a2d(char ch) +{ + if (ch >= '0' && ch <= '9') + return ch - '0'; + else if (ch >= 'a' && ch <= 'f') + return ch - 'a' + 10; + else if (ch >= 'A' && ch <= 'F') + return ch - 'A' + 10; + else + return -1; +} + +static char a2i(char ch, char **src, int base, int *nump) +{ + char *p = *src; + int num = 0; + int digit; + while ((digit = a2d(ch)) >= 0) { + if (digit > base) + break; + num = num * base + digit; + ch = *p++; + } + *src = p; + *nump = num; + return ch; +} + +static void putchw(void *putp, putcf putf, int n, char z, char *bf) +{ + char fc = z ? '0' : ' '; + char ch; + char *p = bf; + while (*p++ && n > 0) + n--; + while (n-- > 0) + putf(putp, fc); + while ((ch = *bf++)) + putf(putp, ch); +} + +void tfp_format(void *putp, putcf putf, char *fmt, va_list va) +{ + char bf[12]; + + char ch; + + while ((ch = *(fmt++))) { + if (ch != '%') + putf(putp, ch); + else { + char lz = 0; +#ifdef PRINTF_LONG_SUPPORT + char lng = 0; +#endif + int w = 0; + ch = *(fmt++); + if (ch == '0') { + ch = *(fmt++); + lz = 1; + } + if (ch >= '0' && ch <= '9') { + ch = a2i(ch, &fmt, 10, &w); + } +#ifdef PRINTF_LONG_SUPPORT + if (ch == 'l') { + ch = *(fmt++); + lng = 1; + } +#endif + switch (ch) { + case 0: + goto abort; + case 'u':{ +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int), 10, 0, bf); + else +#endif + ui2a(va_arg(va, unsigned int), 10, 0, bf); + putchw(putp, putf, w, lz, bf); + break; + } + case 'd':{ +#ifdef PRINTF_LONG_SUPPORT + if (lng) + li2a(va_arg(va, unsigned long int), bf); + else +#endif + i2a(va_arg(va, int), bf); + putchw(putp, putf, w, lz, bf); + break; + } + case 'x': + case 'X': +#ifdef PRINTF_LONG_SUPPORT + if (lng) + uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf); + else +#endif + ui2a(va_arg(va, unsigned int), 16, (ch == 'X'), bf); + putchw(putp, putf, w, lz, bf); + break; + case 'c': + putf(putp, (char) (va_arg(va, int))); + break; + case 's': + putchw(putp, putf, w, 0, va_arg(va, char *)); + break; + case '%': + putf(putp, ch); + default: + break; + } + } + } + abort:; +} + + +void init_printf(void *putp, void (*putf) (void *, char)) +{ + stdout_putf = putf; + stdout_putp = putp; +} + +void tfp_printf(char *fmt, ...) +{ + va_list va; + va_start(va, fmt); + tfp_format(stdout_putp, stdout_putf, fmt, va); + va_end(va); + while (!uartTransmitEmpty()); +} + +static void putcp(void *p, char c) +{ + *(*((char **) p))++ = c; +} + + + +void tfp_sprintf(char *s, char *fmt, ...) +{ + va_list va; + va_start(va, fmt); + tfp_format(&s, putcp, fmt, va); + putcp(&s, 0); + va_end(va); +} diff --git a/src/baseflight/src/printf.h b/src/baseflight/src/printf.h new file mode 100644 index 0000000000..34612d416a --- /dev/null +++ b/src/baseflight/src/printf.h @@ -0,0 +1,121 @@ +/* +File: printf.h + +Copyright (c) 2004,2012 Kustaa Nyholm / SpareTimeLabs + +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +Redistributions of source code must retain the above copyright notice, this list +of conditions and the following disclaimer. + +Redistributions in binary form must reproduce the above copyright notice, this +list of conditions and the following disclaimer in the documentation and/or other +materials provided with the distribution. + +Neither the name of the Kustaa Nyholm or SpareTimeLabs nor the names of its +contributors may be used to endorse or promote products derived from this software +without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. +IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, +INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT +NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, +OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, +WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY +OF SUCH DAMAGE. + +---------------------------------------------------------------------- + +This library is realy just two files: 'printf.h' and 'printf.c'. + +They provide a simple and small (+200 loc) printf functionality to +be used in embedded systems. + +I've found them so usefull in debugging that I do not bother with a +debugger at all. + +They are distributed in source form, so to use them, just compile them +into your project. + +Two printf variants are provided: printf and sprintf. + +The formats supported by this implementation are: 'd' 'u' 'c' 's' 'x' 'X'. + +Zero padding and field width are also supported. + +If the library is compiled with 'PRINTF_SUPPORT_LONG' defined then the +long specifier is also +supported. Note that this will pull in some long math routines (pun intended!) +and thus make your executable noticably longer. + +The memory foot print of course depends on the target cpu, compiler and +compiler options, but a rough guestimate (based on a H8S target) is about +1.4 kB for code and some twenty 'int's and 'char's, say 60 bytes of stack space. +Not too bad. Your milage may vary. By hacking the source code you can +get rid of some hunred bytes, I'm sure, but personally I feel the balance of +functionality and flexibility versus code size is close to optimal for +many embedded systems. + +To use the printf you need to supply your own character output function, +something like : + +void putc ( void* p, char c) + { + while (!SERIAL_PORT_EMPTY) ; + SERIAL_PORT_TX_REGISTER = c; + } + +Before you can call printf you need to initialize it to use your +character output function with something like: + +init_printf(NULL,putc); + +Notice the 'NULL' in 'init_printf' and the parameter 'void* p' in 'putc', +the NULL (or any pointer) you pass into the 'init_printf' will eventually be +passed to your 'putc' routine. This allows you to pass some storage space (or +anything realy) to the character output function, if necessary. +This is not often needed but it was implemented like that because it made +implementing the sprintf function so neat (look at the source code). + +The code is re-entrant, except for the 'init_printf' function, so it +is safe to call it from interupts too, although this may result in mixed output. +If you rely on re-entrancy, take care that your 'putc' function is re-entrant! + +The printf and sprintf functions are actually macros that translate to +'tfp_printf' and 'tfp_sprintf'. This makes it possible +to use them along with 'stdio.h' printf's in a single source file. +You just need to undef the names before you include the 'stdio.h'. +Note that these are not function like macros, so if you have variables +or struct members with these names, things will explode in your face. +Without variadic macros this is the best we can do to wrap these +fucnction. If it is a problem just give up the macros and use the +functions directly or rename them. + +For further details see source code. + +regs Kusti, 23.10.2004 +*/ + + +#ifndef __TFP_PRINTF__ +#define __TFP_PRINTF__ + +#include + +void init_printf(void *putp, void (*putf) (void *, char)); + +void tfp_printf(char *fmt, ...); +void tfp_sprintf(char *s, char *fmt, ...); + +void tfp_format(void *putp, void (*putf) (void *, char), char *fmt, va_list va); + +#define printf tfp_printf +#define sprintf tfp_sprintf + +#endif diff --git a/src/baseflight/src/sensors.c b/src/baseflight/src/sensors.c new file mode 100755 index 0000000000..73645139ed --- /dev/null +++ b/src/baseflight/src/sensors.c @@ -0,0 +1,561 @@ +#include "board.h" +#include "mw.h" + +uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode. +uint16_t calibratingG = 0; +uint16_t acc_1G = 256; // this is the 1G measured acceleration. +int16_t heading, magHold; + +extern uint16_t InflightcalibratingA; +extern int16_t AccInflightCalibrationArmed; +extern uint16_t AccInflightCalibrationMeasurementDone; +extern uint16_t AccInflightCalibrationSavetoEEProm; +extern uint16_t AccInflightCalibrationActive; +extern uint16_t batteryWarningVoltage; +extern uint8_t batteryCellCount; +extern float magneticDeclination; + +sensor_t acc; // acc access functions +sensor_t gyro; // gyro access functions +baro_t baro; // barometer access functions +uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected + +#ifdef FY90Q +// FY90Q analog gyro/acc +void sensorsAutodetect(void) +{ + adcSensorInit(&acc, &gyro); +} +#else +// AfroFlight32 i2c sensors +void sensorsAutodetect(void) +{ + int16_t deg, min; + drv_adxl345_config_t acc_params; + bool haveMpu6k = false; + bool havel3g4200d = false; + + // Autodetect gyro hardware. We have MPU3050 or MPU6050. + if (mpu6050Detect(&acc, &gyro, cfg.mpu6050_scale)) { + // this filled up acc.* struct with init values + haveMpu6k = true; + } else if (l3g4200dDetect(&gyro)) { + havel3g4200d = true; + } else if (!mpu3050Detect(&gyro)) { + // if this fails, we get a beep + blink pattern. we're doomed, no gyro or i2c error. + failureMode(3); + } + + // Accelerometer. Fuck it. Let user break shit. +retry: + switch (cfg.acc_hardware) { + case 0: // autodetect + case 1: // ADXL345 + acc_params.useFifo = false; + acc_params.dataRate = 800; // unused currently + if (adxl345Detect(&acc_params, &acc)) + accHardware = ACC_ADXL345; + if (cfg.acc_hardware == ACC_ADXL345) + break; + ; // fallthrough + case 2: // MPU6050 + if (haveMpu6k) { + mpu6050Detect(&acc, &gyro, cfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct + accHardware = ACC_MPU6050; + if (cfg.acc_hardware == ACC_MPU6050) + break; + } + ; // fallthrough + case 3: // MMA8452 + if (mma8452Detect(&acc)) { + accHardware = ACC_MMA8452; + if (cfg.acc_hardware == ACC_MMA8452) + break; + } + } + + // Found anything? Check if user fucked up or ACC is really missing. + if (accHardware == ACC_DEFAULT) { + if (cfg.acc_hardware > ACC_DEFAULT) { + // Nothing was found and we have a forced sensor type. Stupid user probably chose a sensor that isn't present. + cfg.acc_hardware = ACC_DEFAULT; + goto retry; + } else { + // We're really screwed + sensorsClear(SENSOR_ACC); + } + } + +#ifdef BARO + // Detect what pressure sensors are available. baro->update() is set to sensor-specific update function + if (!ms5611Detect(&baro)) { + // ms5611 disables BMP085, and tries to initialize + check PROM crc. if this works, we have a baro + if (!bmp085Detect(&baro)) { + // if both failed, we don't have anything + sensorsClear(SENSOR_BARO); + } + } +#endif + + // Now time to init things, acc first + if (sensors(SENSOR_ACC)) + acc.init(); + // this is safe because either mpu6050 or mpu3050 or lg3d20 sets it, and in case of fail, we never get here. + gyro.init(); + + // todo: this is driver specific :( + if (havel3g4200d) { + l3g4200dConfig(cfg.gyro_lpf); + } else { + if (!haveMpu6k) + mpu3050Config(cfg.gyro_lpf); + } + +#ifdef MAG + if (!hmc5883lDetect()) + sensorsClear(SENSOR_MAG); +#endif + + // calculate magnetic declination + deg = cfg.mag_declination / 100; + min = cfg.mag_declination % 100; + magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units +} +#endif + +uint16_t batteryAdcToVoltage(uint16_t src) +{ + // calculate battery voltage based on ADC reading + // result is Vbatt in 0.1V steps. 3.3V = ADC Vref, 4095 = 12bit adc, 110 = 11:1 voltage divider (10k:1k) * 10 for 0.1V + return (((src) * 3.3f) / 4095) * cfg.vbatscale; +} + +void batteryInit(void) +{ + uint32_t i; + uint32_t voltage = 0; + + // average up some voltage readings + for (i = 0; i < 32; i++) { + voltage += adcGetChannel(ADC_BATTERY); + delay(10); + } + + voltage = batteryAdcToVoltage((uint16_t)(voltage / 32)); + + // autodetect cell count, going from 2S..6S + for (i = 2; i < 6; i++) { + if (voltage < i * cfg.vbatmaxcellvoltage) + break; + } + batteryCellCount = i; + batteryWarningVoltage = i * cfg.vbatmincellvoltage; // 3.3V per cell minimum, configurable in CLI +} + +// ALIGN_GYRO = 0, +// ALIGN_ACCEL = 1, +// ALIGN_MAG = 2 +static void alignSensors(uint8_t type, int16_t *data) +{ + int i; + int16_t tmp[3]; + + // make a copy :( + tmp[0] = data[0]; + tmp[1] = data[1]; + tmp[2] = data[2]; + + for (i = 0; i < 3; i++) { + int8_t axis = cfg.align[type][i]; + if (axis > 0) + data[axis - 1] = tmp[i]; + else + data[-axis - 1] = -tmp[i]; + } +} + +static void ACC_Common(void) +{ + static int32_t a[3]; + int axis; + + if (calibratingA > 0) { + for (axis = 0; axis < 3; axis++) { + // Reset a[axis] at start of calibration + if (calibratingA == 400) + a[axis] = 0; + // Sum up 400 readings + a[axis] += accADC[axis]; + // Clear global variables for next reading + accADC[axis] = 0; + cfg.accZero[axis] = 0; + } + // Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration + if (calibratingA == 1) { + cfg.accZero[ROLL] = a[ROLL] / 400; + cfg.accZero[PITCH] = a[PITCH] / 400; + cfg.accZero[YAW] = a[YAW] / 400 - acc_1G; // for nunchuk 200=1G + cfg.angleTrim[ROLL] = 0; + cfg.angleTrim[PITCH] = 0; + writeParams(1); // write accZero in EEPROM + } + calibratingA--; + } + + if (feature(FEATURE_INFLIGHT_ACC_CAL)) { + static int32_t b[3]; + static int16_t accZero_saved[3] = { 0, 0, 0 }; + static int16_t angleTrim_saved[2] = { 0, 0 }; + // Saving old zeropoints before measurement + if (InflightcalibratingA == 50) { + accZero_saved[ROLL] = cfg.accZero[ROLL]; + accZero_saved[PITCH] = cfg.accZero[PITCH]; + accZero_saved[YAW] = cfg.accZero[YAW]; + angleTrim_saved[ROLL] = cfg.angleTrim[ROLL]; + angleTrim_saved[PITCH] = cfg.angleTrim[PITCH]; + } + if (InflightcalibratingA > 0) { + for (axis = 0; axis < 3; axis++) { + // Reset a[axis] at start of calibration + if (InflightcalibratingA == 50) + b[axis] = 0; + // Sum up 50 readings + b[axis] += accADC[axis]; + // Clear global variables for next reading + accADC[axis] = 0; + cfg.accZero[axis] = 0; + } + // all values are measured + if (InflightcalibratingA == 1) { + AccInflightCalibrationActive = 0; + AccInflightCalibrationMeasurementDone = 1; + toggleBeep = 2; // buzzer for indicatiing the end of calibration + // recover saved values to maintain current flight behavior until new values are transferred + cfg.accZero[ROLL] = accZero_saved[ROLL]; + cfg.accZero[PITCH] = accZero_saved[PITCH]; + cfg.accZero[YAW] = accZero_saved[YAW]; + cfg.angleTrim[ROLL] = angleTrim_saved[ROLL]; + cfg.angleTrim[PITCH] = angleTrim_saved[PITCH]; + } + InflightcalibratingA--; + } + // Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration + if (AccInflightCalibrationSavetoEEProm == 1) { // the copter is landed, disarmed and the combo has been done again + AccInflightCalibrationSavetoEEProm = 0; + cfg.accZero[ROLL] = b[ROLL] / 50; + cfg.accZero[PITCH] = b[PITCH] / 50; + cfg.accZero[YAW] = b[YAW] / 50 - acc_1G; // for nunchuk 200=1G + cfg.angleTrim[ROLL] = 0; + cfg.angleTrim[PITCH] = 0; + writeParams(1); // write accZero in EEPROM + } + } + + accADC[ROLL] -= cfg.accZero[ROLL]; + accADC[PITCH] -= cfg.accZero[PITCH]; + accADC[YAW] -= cfg.accZero[YAW]; +} + +void ACC_getADC(void) +{ + acc.read(accADC); + // if we have CUSTOM alignment configured, user is "assumed" to know what they're doing + if (cfg.align[ALIGN_ACCEL][0]) + alignSensors(ALIGN_ACCEL, accADC); + else + acc.align(accADC); + + ACC_Common(); +} + +#ifdef BARO +void Baro_update(void) +{ + static uint32_t baroDeadline = 0; + static uint8_t state = 0; + int32_t pressure; + + if ((int32_t)(currentTime - baroDeadline) < 0) + return; + + baroDeadline = currentTime; + + switch (state) { + case 0: + baro.start_ut(); + state++; + baroDeadline += baro.ut_delay; + break; + case 1: + baro.get_ut(); + state++; + break; + case 2: + baro.start_up(); + state++; + baroDeadline += baro.up_delay; + break; + case 3: + baro.get_up(); + pressure = baro.calculate(); + BaroAlt = (1.0f - pow(pressure / 101325.0f, 0.190295f)) * 4433000.0f; // centimeter + state = 0; + baroDeadline += baro.repeat_delay; + break; + } +} +#endif /* BARO */ + +typedef struct stdev_t +{ + float m_oldM, m_newM, m_oldS, m_newS; + int m_n; +} stdev_t; + +static void devClear(stdev_t *dev) +{ + dev->m_n = 0; +} + +static void devPush(stdev_t *dev, float x) +{ + dev->m_n++; + if (dev->m_n == 1) { + dev->m_oldM = dev->m_newM = x; + dev->m_oldS = 0.0f; + } else { + dev->m_newM = dev->m_oldM + (x - dev->m_oldM) / dev->m_n; + dev->m_newS = dev->m_oldS + (x - dev->m_oldM) * (x - dev->m_newM); + dev->m_oldM = dev->m_newM; + dev->m_oldS = dev->m_newS; + } +} + +static float devVariance(stdev_t *dev) +{ + return ((dev->m_n > 1) ? dev->m_newS / (dev->m_n - 1) : 0.0f); +} + +static float devStandardDeviation(stdev_t *dev) +{ + return sqrtf(devVariance(dev)); +} + +static void GYRO_Common(void) +{ + int axis; + static int16_t previousGyroADC[3] = { 0, 0, 0 }; + static int32_t g[3]; + static stdev_t var[3]; + + if (calibratingG > 0) { + for (axis = 0; axis < 3; axis++) { + // Reset g[axis] at start of calibration + if (calibratingG == 1000) { + g[axis] = 0; + devClear(&var[axis]); + } + // Sum up 1000 readings + g[axis] += gyroADC[axis]; + devPush(&var[axis], gyroADC[axis]); + // Clear global variables for next reading + gyroADC[axis] = 0; + gyroZero[axis] = 0; + if (calibratingG == 1) { + float dev = devStandardDeviation(&var[axis]); + // check deviation and startover if idiot was moving the model + if (cfg.moron_threshold && dev > cfg.moron_threshold) { + calibratingG = 1000; + devClear(&var[0]); + devClear(&var[1]); + devClear(&var[2]); + g[0] = g[1] = g[2] = 0; + continue; + } + gyroZero[axis] = g[axis] / 1000; + blinkLED(10, 15, 1); + } + } + calibratingG--; + } + for (axis = 0; axis < 3; axis++) { + gyroADC[axis] -= gyroZero[axis]; + //anti gyro glitch, limit the variation between two consecutive readings + gyroADC[axis] = constrain(gyroADC[axis], previousGyroADC[axis] - 800, previousGyroADC[axis] + 800); + previousGyroADC[axis] = gyroADC[axis]; + } +} + +void Gyro_getADC(void) +{ + // range: +/- 8192; +/- 2000 deg/sec + gyro.read(gyroADC); + // if we have CUSTOM alignment configured, user is "assumed" to know what they're doing + if (cfg.align[ALIGN_GYRO][0]) + alignSensors(ALIGN_GYRO, gyroADC); + else + gyro.align(gyroADC); + + GYRO_Common(); +} + +#ifdef MAG +static float magCal[3] = { 1.0, 1.0, 1.0 }; // gain for each axis, populated at sensor init +static uint8_t magInit = 0; + +static void Mag_getRawADC(void) +{ + hmc5883lRead(magADC); + + // Default mag orientation is -2, -3, 1 or + // no way? is THIS finally the proper orientation?? (by GrootWitBaas) + // magADC[ROLL] = rawADC[2]; // X + // magADC[PITCH] = -rawADC[0]; // Y + // magADC[YAW] = -rawADC[1]; // Z + alignSensors(ALIGN_MAG, magADC); +} + +void Mag_init(void) +{ + uint8_t calibration_gain = 0x60; // HMC5883 +#if 1 + uint32_t numAttempts = 0, good_count = 0; + bool success = false; + uint16_t expected_x = 766; // default values for HMC5883 + uint16_t expected_yz = 713; + float gain_multiple = 660.0f / 1090.0f; // adjustment for runtime vs calibration gain + float cal[3]; + + // initial calibration + hmc5883lInit(); + + magCal[0] = 0; + magCal[1] = 0; + magCal[2] = 0; + + while (success == false && numAttempts < 20 && good_count < 5) { + // record number of attempts at initialisation + numAttempts++; + // enter calibration mode + hmc5883lCal(calibration_gain); + delay(100); + Mag_getRawADC(); + delay(10); + + cal[0] = fabsf(expected_x / (float)magADC[ROLL]); + cal[1] = fabsf(expected_yz / (float)magADC[PITCH]); + cal[2] = fabsf(expected_yz / (float)magADC[ROLL]); + + if (cal[0] > 0.7f && cal[0] < 1.3f && cal[1] > 0.7f && cal[1] < 1.3f && cal[2] > 0.7f && cal[2] < 1.3f) { + good_count++; + magCal[0] += cal[0]; + magCal[1] += cal[1]; + magCal[2] += cal[2]; + } + } + + if (good_count >= 5) { + magCal[0] = magCal[0] * gain_multiple / (float)good_count; + magCal[1] = magCal[1] * gain_multiple / (float)good_count; + magCal[2] = magCal[2] * gain_multiple / (float)good_count; + success = true; + } else { + /* best guess */ + magCal[0] = 1.0f; + magCal[1] = 1.0f; + magCal[2] = 1.0f; + } + + hmc5883lFinishCal(); +#else + // initial calibration + hmc5883lInit(); + + magCal[0] = 0; + magCal[1] = 0; + magCal[2] = 0; + + // enter calibration mode + hmc5883lCal(calibration_gain); + delay(100); + Mag_getRawADC(); + delay(10); + + magCal[ROLL] = 1160.0f / abs(magADC[ROLL]); + magCal[PITCH] = 1160.0f / abs(magADC[PITCH]); + magCal[YAW] = 1080.0f / abs(magADC[YAW]); + + hmc5883lFinishCal(); +#endif + + magInit = 1; +} + +void Mag_getADC(void) +{ + static uint32_t t, tCal = 0; + static int16_t magZeroTempMin[3]; + static int16_t magZeroTempMax[3]; + uint32_t axis; + + if ((int32_t)(currentTime - t) < 0) + return; //each read is spaced by 100ms + t = currentTime + 100000; + + // Read mag sensor + Mag_getRawADC(); + + magADC[ROLL] = magADC[ROLL] * magCal[ROLL]; + magADC[PITCH] = magADC[PITCH] * magCal[PITCH]; + magADC[YAW] = magADC[YAW] * magCal[YAW]; + + if (f.CALIBRATE_MAG) { + tCal = t; + for (axis = 0; axis < 3; axis++) { + cfg.magZero[axis] = 0; + magZeroTempMin[axis] = magADC[axis]; + magZeroTempMax[axis] = magADC[axis]; + } + f.CALIBRATE_MAG = 0; + } + + if (magInit) { // we apply offset only once mag calibration is done + magADC[ROLL] -= cfg.magZero[ROLL]; + magADC[PITCH] -= cfg.magZero[PITCH]; + magADC[YAW] -= cfg.magZero[YAW]; + } + + if (tCal != 0) { + if ((t - tCal) < 30000000) { // 30s: you have 30s to turn the multi in all directions + LED0_TOGGLE; + for (axis = 0; axis < 3; axis++) { + if (magADC[axis] < magZeroTempMin[axis]) + magZeroTempMin[axis] = magADC[axis]; + if (magADC[axis] > magZeroTempMax[axis]) + magZeroTempMax[axis] = magADC[axis]; + } + } else { + tCal = 0; + for (axis = 0; axis < 3; axis++) + cfg.magZero[axis] = (magZeroTempMin[axis] + magZeroTempMax[axis]) / 2; // Calculate offsets + writeParams(1); + } + } +} +#endif + +#ifdef SONAR + +void Sonar_init(void) +{ + hcsr04_init(sonar_rc78); + sensorsSet(SENSOR_SONAR); + sonarAlt = 0; +} + +void Sonar_update(void) +{ + hcsr04_get_distance(&sonarAlt); +} + +#endif diff --git a/src/baseflight/src/serial.c b/src/baseflight/src/serial.c new file mode 100755 index 0000000000..d609f5ba0c --- /dev/null +++ b/src/baseflight/src/serial.c @@ -0,0 +1,462 @@ +#include "board.h" +#include "mw.h" + +// Multiwii Serial Protocol 0 +#define MSP_VERSION 0 +#define PLATFORM_32BIT 0x80000000 + +#define MSP_IDENT 100 //out message multitype + version +#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation +#define MSP_RAW_IMU 102 //out message 9 DOF +#define MSP_SERVO 103 //out message 8 servos +#define MSP_MOTOR 104 //out message 8 motors +#define MSP_RC 105 //out message 8 rc chan +#define MSP_RAW_GPS 106 //out message fix, numsat, lat, lon, alt, speed +#define MSP_COMP_GPS 107 //out message distance home, direction home +#define MSP_ATTITUDE 108 //out message 2 angles 1 heading +#define MSP_ALTITUDE 109 //out message 1 altitude +#define MSP_BAT 110 //out message vbat, powermetersum +#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID +#define MSP_PID 112 //out message up to 16 P I D (8 are used) +#define MSP_BOX 113 //out message up to 16 checkbox (11 are used) +#define MSP_MISC 114 //out message powermeter trig + 8 free for future use +#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI +#define MSP_BOXNAMES 116 //out message the aux switch names +#define MSP_PIDNAMES 117 //out message the PID names +#define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold + +#define MSP_SET_RAW_RC 200 //in message 8 rc chan +#define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed +#define MSP_SET_PID 202 //in message up to 16 P I D (8 are used) +#define MSP_SET_BOX 203 //in message up to 16 checkbox (11 are used) +#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID +#define MSP_ACC_CALIBRATION 205 //in message no param +#define MSP_MAG_CALIBRATION 206 //in message no param +#define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use +#define MSP_RESET_CONF 208 //in message no param +#define MSP_WP_SET 209 //in message sets a given WP (WP#,lat, lon, alt, flags) + +#define MSP_EEPROM_WRITE 250 //in message no param + +#define MSP_DEBUGMSG 253 //out message debug string buffer +#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4 + +#define MSP_ACC_TRIM 240 //out message get acc angle trim values +#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values + +#define INBUF_SIZE 64 + +static const char boxnames[] = + "ANGLE;" + "HORIZON;" + "BARO;" + "MAG;" + "CAMSTAB;" + "CAMTRIG;" + "ARM;" + "GPS HOME;" + "GPS HOLD;" + "PASSTHRU;" + "HEADFREE;" + "BEEPER;" + "LEDMAX;" + "LLIGHTS;" + "HEADADJ;"; + +static const char pidnames[] = + "ROLL;" + "PITCH;" + "YAW;" + "ALT;" + "Pos;" + "PosR;" + "NavR;" + "LEVEL;" + "MAG;" + "VEL;"; + +static uint8_t checksum, indRX, inBuf[INBUF_SIZE]; +static uint8_t cmdMSP; +static bool guiConnected = false; +// signal that we're in cli mode +uint8_t cliMode = 0; + +void serialize32(uint32_t a) +{ + static uint8_t t; + t = a; + uartWrite(t); + checksum ^= t; + t = a >> 8; + uartWrite(t); + checksum ^= t; + t = a >> 16; + uartWrite(t); + checksum ^= t; + t = a >> 24; + uartWrite(t); + checksum ^= t; +} + +void serialize16(int16_t a) +{ + static uint8_t t; + t = a; + uartWrite(t); + checksum ^= t; + t = a >> 8 & 0xff; + uartWrite(t); + checksum ^= t; +} + +void serialize8(uint8_t a) +{ + uartWrite(a); + checksum ^= a; +} + +uint8_t read8(void) +{ + return inBuf[indRX++] & 0xff; +} + +uint16_t read16(void) +{ + uint16_t t = read8(); + t += (uint16_t) read8() << 8; + return t; +} + +uint32_t read32(void) +{ + uint32_t t = read16(); + t += (uint32_t) read16() << 16; + return t; +} + +void headSerialResponse(uint8_t err, uint8_t s) +{ + serialize8('$'); + serialize8('M'); + serialize8(err ? '!' : '>'); + checksum = 0; // start calculating a new checksum + serialize8(s); + serialize8(cmdMSP); +} + +void headSerialReply(uint8_t s) +{ + headSerialResponse(0, s); +} + +void headSerialError(uint8_t s) +{ + headSerialResponse(1, s); +} + +void tailSerialReply(void) +{ + serialize8(checksum); +} + +void serializeNames(const char *s) +{ + const char *c; + for (c = s; *c; c++) + serialize8(*c); +} + +void serialInit(uint32_t baudrate) +{ + uartInit(baudrate); +} + +static void evaluateCommand(void) +{ + uint32_t i; + uint8_t wp_no; + + switch (cmdMSP) { + case MSP_SET_RAW_RC: + for (i = 0; i < 8; i++) + rcData[i] = read16(); + headSerialReply(0); + break; + case MSP_SET_ACC_TRIM: + cfg.angleTrim[PITCH] = read16(); + cfg.angleTrim[ROLL] = read16(); + headSerialReply(0); + break; + case MSP_SET_RAW_GPS: + f.GPS_FIX = read8(); + GPS_numSat = read8(); + GPS_coord[LAT] = read32(); + GPS_coord[LON] = read32(); + GPS_altitude = read16(); + GPS_speed = read16(); + GPS_update |= 2; // New data signalisation to GPS functions + headSerialReply(0); + break; + case MSP_SET_PID: + for (i = 0; i < PIDITEMS; i++) { + cfg.P8[i] = read8(); + cfg.I8[i] = read8(); + cfg.D8[i] = read8(); + } + headSerialReply(0); + break; + case MSP_SET_BOX: + for (i = 0; i < CHECKBOXITEMS; i++) + cfg.activate[i] = read16(); + headSerialReply(0); + break; + case MSP_SET_RC_TUNING: + cfg.rcRate8 = read8(); + cfg.rcExpo8 = read8(); + cfg.rollPitchRate = read8(); + cfg.yawRate = read8(); + cfg.dynThrPID = read8(); + cfg.thrMid8 = read8(); + cfg.thrExpo8 = read8(); + headSerialReply(0); + break; + case MSP_SET_MISC: + headSerialReply(0); + break; + case MSP_IDENT: + headSerialReply(7); + serialize8(VERSION); // multiwii version + serialize8(cfg.mixerConfiguration); // type of multicopter + serialize8(MSP_VERSION); // MultiWii Serial Protocol Version + serialize32(PLATFORM_32BIT); // "capability" + break; + case MSP_STATUS: + headSerialReply(10); + serialize16(cycleTime); + serialize16(i2cGetErrorCounter()); + serialize16(sensors(SENSOR_ACC) | sensors(SENSOR_BARO) << 1 | sensors(SENSOR_MAG) << 2 | sensors(SENSOR_GPS) << 3 | sensors(SENSOR_SONAR) << 4); + serialize32(f.ANGLE_MODE << BOXANGLE | f.HORIZON_MODE << BOXHORIZON | f.BARO_MODE << BOXBARO | f.MAG_MODE << BOXMAG | f.ARMED << BOXARM | + rcOptions[BOXCAMSTAB] << BOXCAMSTAB | rcOptions[BOXCAMTRIG] << BOXCAMTRIG | + f.GPS_HOME_MODE << BOXGPSHOME | f.GPS_HOLD_MODE << BOXGPSHOLD | f.HEADFREE_MODE << BOXHEADFREE | f.PASSTHRU_MODE << BOXPASSTHRU | + rcOptions[BOXBEEPERON] << BOXBEEPERON | rcOptions[BOXLEDMAX] << BOXLEDMAX | rcOptions[BOXLLIGHTS] << BOXLLIGHTS | rcOptions[BOXHEADADJ] << BOXHEADADJ); + break; + case MSP_RAW_IMU: + headSerialReply(18); + for (i = 0; i < 3; i++) + serialize16(accSmooth[i]); + for (i = 0; i < 3; i++) + serialize16(gyroData[i]); + for (i = 0; i < 3; i++) + serialize16(magADC[i]); + break; + case MSP_SERVO: + headSerialReply(16); + for (i = 0; i < 8; i++) + serialize16(servo[i]); + break; + case MSP_MOTOR: + headSerialReply(16); + for (i = 0; i < 8; i++) + serialize16(motor[i]); + break; + case MSP_RC: + headSerialReply(16); + for (i = 0; i < 8; i++) + serialize16(rcData[i]); + break; + case MSP_RAW_GPS: + headSerialReply(14); + serialize8(f.GPS_FIX); + serialize8(GPS_numSat); + serialize32(GPS_coord[LAT]); + serialize32(GPS_coord[LON]); + serialize16(GPS_altitude); + serialize16(GPS_speed); + break; + case MSP_COMP_GPS: + headSerialReply(5); + serialize16(GPS_distanceToHome); + serialize16(GPS_directionToHome); + serialize8(GPS_update & 1); + break; + case MSP_ATTITUDE: + headSerialReply(8); + for (i = 0; i < 2; i++) + serialize16(angle[i]); + serialize16(heading); + serialize16(headFreeModeHold); + break; + case MSP_ALTITUDE: + headSerialReply(4); + serialize32(EstAlt); + break; + case MSP_BAT: + headSerialReply(3); + serialize8(vbat); + serialize16(0); // power meter trash + break; + case MSP_RC_TUNING: + headSerialReply(7); + serialize8(cfg.rcRate8); + serialize8(cfg.rcExpo8); + serialize8(cfg.rollPitchRate); + serialize8(cfg.yawRate); + serialize8(cfg.dynThrPID); + serialize8(cfg.thrMid8); + serialize8(cfg.thrExpo8); + break; + case MSP_PID: + headSerialReply(3 * PIDITEMS); + for (i = 0; i < PIDITEMS; i++) { + serialize8(cfg.P8[i]); + serialize8(cfg.I8[i]); + serialize8(cfg.D8[i]); + } + break; + case MSP_BOX: + headSerialReply(2 * CHECKBOXITEMS); + for (i = 0; i < CHECKBOXITEMS; i++) + serialize16(cfg.activate[i]); + break; + case MSP_BOXNAMES: + headSerialReply(sizeof(boxnames) - 1); + serializeNames(boxnames); + break; + case MSP_PIDNAMES: + headSerialReply(sizeof(pidnames) - 1); + serializeNames(pidnames); + break; + case MSP_MISC: + headSerialReply(2); + serialize16(0); // intPowerTrigger1 + break; + case MSP_MOTOR_PINS: + headSerialReply(8); + for (i = 0; i < 8; i++) + serialize8(i + 1); + break; + case MSP_WP: + wp_no = read8(); // get the wp number + headSerialReply(12); + if (wp_no == 0) { + serialize8(0); // wp0 + serialize32(GPS_home[LAT]); + serialize32(GPS_home[LON]); + serialize16(0); // altitude will come here + serialize8(0); // nav flag will come here + } else if (wp_no == 16) { + serialize8(16); // wp16 + serialize32(GPS_hold[LAT]); + serialize32(GPS_hold[LON]); + serialize16(0); // altitude will come here + serialize8(0); // nav flag will come here + } + break; + case MSP_RESET_CONF: + checkFirstTime(true); + headSerialReply(0); + break; + case MSP_ACC_CALIBRATION: + calibratingA = 400; + headSerialReply(0); + break; + case MSP_MAG_CALIBRATION: + f.CALIBRATE_MAG = 1; + headSerialReply(0); + break; + case MSP_EEPROM_WRITE: + writeParams(0); + headSerialReply(0); + break; + case MSP_ACC_TRIM: + headSerialReply(4); + serialize16(cfg.angleTrim[PITCH]); + serialize16(cfg.angleTrim[ROLL]); + break; + case MSP_DEBUG: + headSerialReply(8); + for (i = 0; i < 4; i++) + serialize16(debug[i]); // 4 variables are here for general monitoring purpose + break; + default: // we do not know how to handle the (valid) message, indicate error MSP $M! + headSerialError(0); + break; + } + tailSerialReply(); +} + +// evaluate all other incoming serial data +static void evaluateOtherData(uint8_t sr) +{ + switch (sr) { + case '#': + cliProcess(); + break; + case 'R': + systemReset(true); // reboot to bootloader + break; + } +} + +void serialCom(void) +{ + uint8_t c; + static uint8_t offset; + static uint8_t dataSize; + static enum _serial_state { + IDLE, + HEADER_START, + HEADER_M, + HEADER_ARROW, + HEADER_SIZE, + HEADER_CMD, + } c_state = IDLE; + + // in cli mode, all uart stuff goes to here. enter cli mode by sending # + if (cliMode) { + cliProcess(); + return; + } + + while (uartAvailable()) { + c = uartRead(); + + if (c_state == IDLE) { + c_state = (c == '$') ? HEADER_START : IDLE; + if (c_state == IDLE) + evaluateOtherData(c); // evaluate all other incoming serial data + } else if (c_state == HEADER_START) { + c_state = (c == 'M') ? HEADER_M : IDLE; + } else if (c_state == HEADER_M) { + c_state = (c == '<') ? HEADER_ARROW : IDLE; + } else if (c_state == HEADER_ARROW) { + if (c > INBUF_SIZE) { // now we are expecting the payload size + c_state = IDLE; + continue; + } + dataSize = c; + offset = 0; + checksum = 0; + indRX = 0; + checksum ^= c; + c_state = HEADER_SIZE; // the command is to follow + guiConnected = true; + } else if (c_state == HEADER_SIZE) { + cmdMSP = c; + checksum ^= c; + c_state = HEADER_CMD; + } else if (c_state == HEADER_CMD && offset < dataSize) { + checksum ^= c; + inBuf[offset++] = c; + } else if (c_state == HEADER_CMD && offset >= dataSize) { + if (checksum == c) { // compare calculated and transferred checksum + evaluateCommand(); // we got a valid packet, evaluate it + } + c_state = IDLE; + } + } + if (!cliMode && !uartAvailable() && feature(FEATURE_TELEMETRY) && f.ARMED) { // The first 2 conditions should never evaluate to true but I'm putting it here anyway - silpstream + sendTelemetry(); + return; + } +} diff --git a/src/baseflight/src/spektrum.c b/src/baseflight/src/spektrum.c new file mode 100644 index 0000000000..cdb6ee10d1 --- /dev/null +++ b/src/baseflight/src/spektrum.c @@ -0,0 +1,87 @@ +#include "board.h" +#include "mw.h" + +// driver for spektrum satellite receiver / sbus using UART2 (freeing up more motor outputs for stuff) + +#define SPEK_MAX_CHANNEL 7 +#define SPEK_FRAME_SIZE 16 +static uint8_t spek_chan_shift; +static uint8_t spek_chan_mask; +static bool rcFrameComplete = false; +static bool spekDataIncoming = false; +volatile uint8_t spekFrame[SPEK_FRAME_SIZE]; +static void spektrumDataReceive(uint16_t c); + +// external vars (ugh) +extern int16_t failsafeCnt; + +void spektrumInit(void) +{ + if (cfg.spektrum_hires) { + // 11 bit frames + spek_chan_shift = 3; + spek_chan_mask = 0x07; + } else { + // 10 bit frames + spek_chan_shift = 2; + spek_chan_mask = 0x03; + } + + uart2Init(115200, spektrumDataReceive, true); +} + +// UART2 Receive ISR callback +static void spektrumDataReceive(uint16_t c) +{ + uint32_t spekTime; + static uint32_t spekTimeLast, spekTimeInterval; + static uint8_t spekFramePosition; + + spekDataIncoming = true; + spekTime = micros(); + spekTimeInterval = spekTime - spekTimeLast; + spekTimeLast = spekTime; + if (spekTimeInterval > 5000) + spekFramePosition = 0; + spekFrame[spekFramePosition] = (uint8_t)c; + if (spekFramePosition == SPEK_FRAME_SIZE - 1) { + rcFrameComplete = true; + failsafeCnt = 0; // clear FailSafe counter + } else { + spekFramePosition++; + } +} + +bool spektrumFrameComplete(void) +{ + return rcFrameComplete; +} + +// static const uint8_t spekRcChannelMap[SPEK_MAX_CHANNEL] = {1, 2, 3, 0, 4, 5, 6}; + +uint16_t spektrumReadRawRC(uint8_t chan) +{ + uint16_t data; + static uint32_t spekChannelData[SPEK_MAX_CHANNEL]; + uint8_t b; + + if (rcFrameComplete) { + for (b = 3; b < SPEK_FRAME_SIZE; b += 2) { + uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift); + if (spekChannel < SPEK_MAX_CHANNEL) + spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b]; + } + rcFrameComplete = false; + } + + if (chan >= SPEK_MAX_CHANNEL || !spekDataIncoming) { + data = cfg.midrc; + } else { + if (cfg.spektrum_hires) + data = 988 + (spekChannelData[cfg.rcmap[chan]] >> 1); // 2048 mode + else + data = 988 + spekChannelData[cfg.rcmap[chan]]; // 1024 mode + } + + return data; +} diff --git a/src/baseflight/src/telemetry.c b/src/baseflight/src/telemetry.c new file mode 100644 index 0000000000..2157852974 --- /dev/null +++ b/src/baseflight/src/telemetry.c @@ -0,0 +1,202 @@ +/* + * FrSky Telemetry implementation by silpstream @ rcgroups + */ +#include "board.h" +#include "mw.h" + +#define CYCLETIME 125 + +#define PROTOCOL_HEADER 0x5E +#define PROTOCOL_TAIL 0x5E + +// Data Ids (bp = before decimal point; af = after decimal point) +// Official data IDs +#define ID_GPS_ALTIDUTE_BP 0x01 +#define ID_GPS_ALTIDUTE_AP 0x09 +#define ID_TEMPRATURE1 0x02 +#define ID_RPM 0x03 +#define ID_FUEL_LEVEL 0x04 +#define ID_TEMPRATURE2 0x05 +#define ID_VOLT 0x06 +#define ID_ALTITUDE_BP 0x10 +#define ID_ALTITUDE_AP 0x21 +#define ID_GPS_SPEED_BP 0x11 +#define ID_GPS_SPEED_AP 0x19 +#define ID_LONGITUDE_BP 0x12 +#define ID_LONGITUDE_AP 0x1A +#define ID_E_W 0x22 +#define ID_LATITUDE_BP 0x13 +#define ID_LATITUDE_AP 0x1B +#define ID_N_S 0x23 +#define ID_COURSE_BP 0x14 +#define ID_COURSE_AP 0x1C +#define ID_DATE_MONTH 0x15 +#define ID_YEAR 0x16 +#define ID_HOUR_MINUTE 0x17 +#define ID_SECOND 0x18 +#define ID_ACC_X 0x24 +#define ID_ACC_Y 0x25 +#define ID_ACC_Z 0x26 +#define ID_VOLTAGE_AMP_BP 0x3A +#define ID_VOLTAGE_AMP_AP 0x3B +#define ID_CURRENT 0x28 +// User defined data IDs +#define ID_GYRO_X 0x40 +#define ID_GYRO_Y 0x41 +#define ID_GYRO_Z 0x42 + +static void sendDataHead(uint8_t id) +{ + uartWrite(PROTOCOL_HEADER); + uartWrite(id); +} + +static void sendTelemetryTail(void) +{ + uartWrite(PROTOCOL_TAIL); +} + +static void serializeFrsky(uint8_t data) +{ + // take care of byte stuffing + if (data == 0x5e) { + uartWrite(0x5d); + uartWrite(0x3e); + } else if (data == 0x5d) { + uartWrite(0x5d); + uartWrite(0x3d); + } else + uartWrite(data); +} + +static void serialize16(int16_t a) +{ + uint8_t t; + t = a; + serializeFrsky(t); + t = a >> 8 & 0xff; + serializeFrsky(t); +} + +static void sendAccel(void) +{ + int i; + + for (i = 0; i < 3; i++) { + sendDataHead(ID_ACC_X + i); + serialize16(((float)accSmooth[i] / acc_1G) * 1000); + } +} + +static void sendBaro(void) +{ + sendDataHead(ID_ALTITUDE_BP); + serialize16(EstAlt / 100); + sendDataHead(ID_ALTITUDE_AP); + serialize16(EstAlt % 100); +} + +static void sendTemperature1(void) +{ + sendDataHead(ID_TEMPRATURE1); + serialize16(telemTemperature1 / 10); +} + +static void sendTime(void) +{ + uint32_t seconds = millis() / 1000; + uint8_t minutes = (seconds / 60) % 60; + + // if we fly for more than an hour, something's wrong anyway + sendDataHead(ID_HOUR_MINUTE); + serialize16(minutes << 8); + sendDataHead(ID_SECOND); + serialize16(seconds % 60); +} + +static void sendGPS(void) +{ + sendDataHead(ID_LATITUDE_BP); + serialize16(abs(GPS_coord[LAT]) / 100000); + sendDataHead(ID_LATITUDE_AP); + serialize16((abs(GPS_coord[LAT]) / 10) % 10000); + + sendDataHead(ID_N_S); + serialize16(GPS_coord[LAT] < 0 ? 'S' : 'N'); + + sendDataHead(ID_LONGITUDE_BP); + serialize16(abs(GPS_coord[LON]) / 100000); + sendDataHead(ID_LONGITUDE_AP); + serialize16((abs(GPS_coord[LON]) / 10) % 10000); + sendDataHead(ID_E_W); + serialize16(GPS_coord[LON] < 0 ? 'W' : 'E'); +} + +static void sendVoltage(void) +{ + uint16_t voltage; + + voltage = (vbat * 110) / 21; + + sendDataHead(ID_VOLTAGE_AMP_BP); + serialize16(voltage / 100); + sendDataHead(ID_VOLTAGE_AMP_AP); + serialize16(((voltage % 100) + 5) / 10); +} + +static void sendHeading(void) +{ + sendDataHead(ID_COURSE_BP); + serialize16(heading); + sendDataHead(ID_COURSE_AP); + serialize16(0); +} + +static bool telemetryEnabled = false; + +void initTelemetry(bool State) +{ + if (State != telemetryEnabled) { + if (State) + serialInit(9600); + else + serialInit(cfg.serial_baudrate); + telemetryEnabled = State; + } +} + +static uint32_t lastCycleTime = 0; +static uint8_t cycleNum = 0; + +void sendTelemetry(void) +{ + if (millis() - lastCycleTime >= CYCLETIME) { + lastCycleTime = millis(); + cycleNum++; + + // Sent every 125ms + sendAccel(); + sendTelemetryTail(); + + if ((cycleNum % 4) == 0) { // Sent every 500ms + sendBaro(); + sendHeading(); + sendTelemetryTail(); + } + + if ((cycleNum % 8) == 0) { // Sent every 1s + sendTemperature1(); + if (feature(FEATURE_VBAT)) + sendVoltage(); + if (sensors(SENSOR_GPS)) + sendGPS(); + sendTelemetryTail(); + } + + if (cycleNum == 40) { //Frame 3: Sent every 5s + cycleNum = 0; + sendTime(); + sendTelemetryTail(); + } + } +} diff --git a/src/baseflight/stm32_flash.ld b/src/baseflight/stm32_flash.ld new file mode 100644 index 0000000000..abd809b4cc --- /dev/null +++ b/src/baseflight/stm32_flash.ld @@ -0,0 +1,150 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F103C8 Device with +** 64KByte FLASH, 20KByte RAM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = 0x20005000; /* end of 10K RAM */ + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 127K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(.bss*) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >RAM + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/baseflight/support/flash.bat b/src/baseflight/support/flash.bat new file mode 100644 index 0000000000..058d745344 --- /dev/null +++ b/src/baseflight/support/flash.bat @@ -0,0 +1,26 @@ +@@echo OFF + +:: User configuration + +:: set your port number. ie: for COM6 , port is 6 +set PORT=2 +:: location of stmflashloader.exe, this is default +set FLASH_LOADER="C:\Program Files (x86)\STMicroelectronics\Software\Flash Loader Demonstrator\STMFlashLoader.exe" +:: path to firmware +set FIRMWARE="D:\baseflight.hex" + +:: ---------------------------------------------- + +mode COM%PORT% BAUD=115200 PARITY=N DATA=8 STOP=1 XON=OFF DTR=OFF RTS=OFF +echo/|set /p ="R" > COM%PORT%: + +TIMEOUT /T 3 + +cd %LOADER_PATH% + +%FLASH_LOADER% ^ + -c --pn %PORT% --br 115200 --db 8 ^ + -i STM32_Med-density_128K ^ + -e --all ^ + -d --fn %FIRMWARE% ^ + -r --a 0x8000000 diff --git a/src/baseflight/support/stmloader/Makefile b/src/baseflight/support/stmloader/Makefile new file mode 100644 index 0000000000..6782ed9528 --- /dev/null +++ b/src/baseflight/support/stmloader/Makefile @@ -0,0 +1,14 @@ +CC = $(CROSS_COMPILE)gcc +AR = $(CROSS_COMPILE)ar +export CC +export AR + +all: + $(CC) -g -o stmloader -I./ \ + loader.c \ + serial.c \ + stmbootloader.c \ + -Wall + +clean: + rm -f stmloader diff --git a/src/baseflight/support/stmloader/loader.c b/src/baseflight/support/stmloader/loader.c new file mode 100644 index 0000000000..e5d6aee34a --- /dev/null +++ b/src/baseflight/support/stmloader/loader.c @@ -0,0 +1,116 @@ +/* + This file is part of AutoQuad. + + AutoQuad is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + AutoQuad is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with AutoQuad. If not, see . + + Copyright © 2011 Bill Nesbitt +*/ + +#include "serial.h" +#include "stmbootloader.h" +#include +#include +#include +#include +#include +#include +#include + +#define DEFAULT_PORT "/dev/ttyUSB0" +#define DEFAULT_BAUD 115200 +#define FIRMWARE_FILENAME "STM32.hex" + +serialStruct_t *s; + +char port[256]; +unsigned int baud; +unsigned char overrideParity; +char firmFile[256]; + +void loaderUsage(void) { + fprintf(stderr, "usage: loader <-h> <-p device_file> <-b baud_rate> <-f firmware_file> <-o>\n"); +} + +unsigned int loaderOptions(int argc, char **argv) { + int ch; + + strncpy(port, DEFAULT_PORT, sizeof(port)); + baud = DEFAULT_BAUD; + overrideParity = 0; + strncpy(firmFile, FIRMWARE_FILENAME, sizeof(firmFile)); + + /* options descriptor */ + static struct option longopts[] = { + { "help", required_argument, NULL, 'h' }, + { "port", required_argument, NULL, 'p' }, + { "baud", required_argument, NULL, 's' }, + { "firm_file", required_argument, NULL, 'f' }, + { "overide_party",no_argument, NULL, 'o' }, + { NULL, 0, NULL, 0 } + }; + + while ((ch = getopt_long(argc, argv, "hp:b:f:o", longopts, NULL)) != -1) + switch (ch) { + case 'h': + loaderUsage(); + exit(0); + break; + case 'p': + strncpy(port, optarg, sizeof(port)); + break; + case 'b': + baud = atoi(optarg); + break; + case 'f': + strncpy(firmFile, optarg, sizeof(firmFile)); + break; + case 'o': + overrideParity = 1; + break; + default: + loaderUsage(); + return 0; + } + argc -= optind; + argv += optind; + + return 1; +} + +int main(int argc, char **argv) { + FILE *fw; + + // init + if (!loaderOptions(argc, argv)) { + fprintf(stderr, "Init failed, aborting\n"); + return 1; + } + + s = initSerial(port, baud, 0); + if (!s) { + fprintf(stderr, "Cannot open serial port '%s', aborting.\n", port); + return 1; + } + + fw = fopen(firmFile, "r"); + if (!fw) { + fprintf(stderr, "Cannot open firmware file '%s', aborting.\n", firmFile); + return 1; + } + else { + printf("Upgrading STM on port %s from %s...\n", port, firmFile); + stmLoader(s, fw, overrideParity); + } + + return 0; +} diff --git a/src/baseflight/support/stmloader/serial.c b/src/baseflight/support/stmloader/serial.c new file mode 100644 index 0000000000..c195f9bc41 --- /dev/null +++ b/src/baseflight/support/stmloader/serial.c @@ -0,0 +1,179 @@ +/* + This file is part of AutoQuad. + + AutoQuad is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + AutoQuad is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with AutoQuad. If not, see . + + Copyright © 2011 Bill Nesbitt +*/ + +#ifndef _GNU_SOURCE +#define _GNU_SOURCE +#endif + +#include "serial.h" +#include +#include +#include +#include +#include +#include +#include + +serialStruct_t *initSerial(const char *port, unsigned int baud, char ctsRts) { + serialStruct_t *s; + struct termios options; + unsigned int brate; + + s = (serialStruct_t *)calloc(1, sizeof(serialStruct_t)); + + s->fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY); + + if (s->fd == -1) { + free(s); + return 0; + } + + fcntl(s->fd, F_SETFL, 0); // clear all flags on descriptor, enable direct I/O + +// bzero(&options, sizeof(options)); +// memset(&options, 0, sizeof(options)); + tcgetattr(s->fd, &options); + +#ifdef B921600 + switch (baud) { + case 9600: + brate = B9600; + break; + case 19200: + brate = B19200; + break; + case 38400: + brate = B38400; + break; + case 57600: + brate = B57600; + break; + case 115200: + brate = B115200; + break; + case 230400: + brate = B230400; + break; + case 460800: + brate = B460800; + break; + case 921600: + brate = B921600; + break; + default: + brate = B115200; + break; + } + options.c_cflag = brate; +#else // APPLE + cfsetispeed(&options, baud); + cfsetospeed(&options, baud); +#endif + + options.c_cflag |= CRTSCTS | CS8 | CLOCAL | CREAD; + options.c_iflag = IGNPAR; + options.c_iflag &= (~(IXON|IXOFF|IXANY)); // turn off software flow control + options.c_oflag = 0; + + /* set input mode (non-canonical, no echo,...) */ + options.c_lflag = 0; + + options.c_cc[VTIME] = 0; /* inter-character timer unused */ + options.c_cc[VMIN] = 1; /* blocking read until 1 chars received */ + +#ifdef CCTS_OFLOW + options.c_cflag |= CCTS_OFLOW; +#endif + + if (!ctsRts) + options.c_cflag &= ~(CRTSCTS); // turn off hardware flow control + + // set the new port options + tcsetattr(s->fd, TCSANOW, &options); + + return s; +} + +void serialFree(serialStruct_t *s) { + if (s) { + if (s->fd) + close(s->fd); + free (s); + } +} + +void serialNoParity(serialStruct_t *s) { + struct termios options; + + tcgetattr(s->fd, &options); // read serial port options + + options.c_cflag &= ~(PARENB | CSTOPB); + + tcsetattr(s->fd, TCSANOW, &options); +} + +void serialEvenParity(serialStruct_t *s) { + struct termios options; + + tcgetattr(s->fd, &options); // read serial port options + + options.c_cflag |= (PARENB); + options.c_cflag &= ~(PARODD | CSTOPB); + + tcsetattr(s->fd, TCSANOW, &options); +} + +void serialWriteChar(serialStruct_t *s, unsigned char c) { + char ret; + + ret = write(s->fd, &c, 1); +} + +void serialWrite(serialStruct_t *s, const char *str, unsigned int len) { + char ret; + + ret = write(s->fd, str, len); +} + +unsigned char serialAvailable(serialStruct_t *s) { + fd_set fdSet; + struct timeval timeout; + + FD_ZERO(&fdSet); + FD_SET(s->fd, &fdSet); + memset((char *)&timeout, 0, sizeof(timeout)); + + if (select(s->fd+1, &fdSet, 0, 0, &timeout) == 1) + return 1; + else + return 0; +} + +void serialFlush(serialStruct_t *s) { + while (serialAvailable(s)) + serialRead(s); +} + +unsigned char serialRead(serialStruct_t *s) { + char ret; + unsigned char c; + + ret = read(s->fd, &c, 1); + + return c; +} diff --git a/src/baseflight/support/stmloader/serial.h b/src/baseflight/support/stmloader/serial.h new file mode 100644 index 0000000000..90beedc781 --- /dev/null +++ b/src/baseflight/support/stmloader/serial.h @@ -0,0 +1,38 @@ +/* + This file is part of AutoQuad. + + AutoQuad is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + AutoQuad is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with AutoQuad. If not, see . + + Copyright © 2011 Bill Nesbitt +*/ + +#ifndef _serial_h +#define _serial_h + +#define INPUT_BUFFER_SIZE 1024 + +typedef struct { + int fd; +} serialStruct_t; + +extern serialStruct_t *initSerial(const char *port, unsigned int baud, char ctsRts); +extern void serialWrite(serialStruct_t *s, const char *str, unsigned int len); +extern void serialWriteChar(serialStruct_t *s, unsigned char c); +extern unsigned char serialAvailable(serialStruct_t *s); +extern void serialFlush(serialStruct_t *s); +extern unsigned char serialRead(serialStruct_t *s); +extern void serialEvenParity(serialStruct_t *s); +extern void serialNoParity(serialStruct_t *s); +extern void serialFree(serialStruct_t *s); + +#endif diff --git a/src/baseflight/support/stmloader/stmbootloader.c b/src/baseflight/support/stmloader/stmbootloader.c new file mode 100644 index 0000000000..75fd187856 --- /dev/null +++ b/src/baseflight/support/stmloader/stmbootloader.c @@ -0,0 +1,341 @@ +/* + This file is part of AutoQuad. + + AutoQuad is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + AutoQuad is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with AutoQuad. If not, see . + + Copyright © 2011 Bill Nesbitt +*/ + +#ifndef _GNU_SOURCE +#define _GNU_SOURCE +#endif + +#include "serial.h" +#include +#include +#include +#include + +#define STM_RETRIES_SHORT 1000 +#define STM_RETRIES_LONG 50000 + +unsigned char getResults[11]; + +unsigned char stmHexToChar(const char *hex) { + char hex1, hex2; + unsigned char nibble1, nibble2; + + // force data to upper case + hex1 = toupper(hex[0]); + hex2 = toupper(hex[1]); + + if (hex1 < 65) + nibble1 = hex1 - 48; + else + nibble1 = hex1 - 55; + + if (hex2 < 65) + nibble2 = hex2 - 48; + else + nibble2 = hex2 - 55; + + return (nibble1 << 4 | nibble2); +} + + +unsigned char stmWaitAck(serialStruct_t *s, int retries) { + unsigned char c; + unsigned int i; + + for (i = 0; i < retries; i++) { + if (serialAvailable(s)) { + c = serialRead(s); + if (c == 0x79) { +// putchar('+'); fflush(stdout); + return 1; + } + if (c == 0x1f) { + putchar('-'); fflush(stdout); + return 0; + } + else { + printf("?%x?", c); fflush(stdout); + return 0; + } + } + usleep(500); + } + + return 0; +} + +unsigned char stmWrite(serialStruct_t *s, const char *hex) { + unsigned char c; + unsigned char ck; + unsigned char i; + + ck = 0; + i = 0; + while (*hex) { + c = stmHexToChar(hex); + serialWrite(s, (char *)&c, 1); + ck ^= c; + hex += 2; + i++; + } + if (i == 1) + ck = 0xff ^ c; + + // send checksum + serialWrite(s, (char *)&ck, 1); + + return stmWaitAck(s, STM_RETRIES_LONG); +} + +void stmWriteCommand(serialStruct_t *s, char *msb, char *lsb, char *len, char *data) { + char startAddress[9]; + char lenPlusData[128]; + char c; + + strncpy(startAddress, msb, sizeof(startAddress)); + strcat(startAddress, lsb); + + sprintf(lenPlusData, "%02x%s", stmHexToChar(len) - 1, data); + + write: + // send WRITE MEMORY command + do { + c = getResults[5]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + + // send address + if (!stmWrite(s, startAddress)) { + putchar('A'); + goto write; + } + + // send len + data + if (!stmWrite(s, lenPlusData)) { + putchar('D'); + goto write; + } + + putchar('='); fflush(stdout); +} + +char *stmHexLoader(serialStruct_t *s, FILE *fp) { + char hexByteCount[3], hexAddressLSB[5], hexRecordType[3], hexData[128]; + char addressMSB[5]; + static char addressJump[9]; + +// bzero(addressJump, sizeof(addressJump)); +// bzero(addressMSB, sizeof(addressMSB)); + memset(addressJump, 0, sizeof(addressJump)); + memset(addressMSB, 0, sizeof(addressMSB)); + + while (fscanf(fp, ":%2s%4s%2s%s\n", hexByteCount, hexAddressLSB, hexRecordType, hexData) != EOF) { + unsigned int byteCount, addressLSB, recordType; + + recordType = stmHexToChar(hexRecordType); + hexData[stmHexToChar(hexByteCount) * 2] = 0; // terminate at CHKSUM + +// printf("Record Type: %d\n", recordType); + switch (recordType) { + case 0x00: + stmWriteCommand(s, addressMSB, hexAddressLSB, hexByteCount, hexData); + break; + case 0x01: + // EOF + return addressJump; + break; + case 0x04: + // MSB of destination 32 bit address + strncpy(addressMSB, hexData, 4); + break; + case 0x05: + // 32 bit address to run after load + strncpy(addressJump, hexData, 8); + break; + } + } + + return 0; +} + +void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity) { + char c; + unsigned char b1, b2, b3; + unsigned char i, n; + char *jumpAddress; + + // turn on parity generation + if (!overrideParity) + serialEvenParity(s); + + top: + printf("Sending R to place Baseflight in bootloader, press a key to continue"); + serialFlush(s); + c = 'R'; + serialWrite(s, &c, 1); + getchar(); + printf("\n"); + + serialFlush(s); + + printf("Poking the MCU to check whether bootloader is alive..."); + + // poke the MCU + do { + printf("p"); fflush(stdout); + c = 0x7f; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_SHORT)); + printf("STM bootloader alive...\n"); + + // send GET command + do { + c = 0x00; + serialWrite(s, &c, 1); + c = 0xff; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + + b1 = serialRead(s); // number of bytes + b2 = serialRead(s); // bootloader version + + for (i = 0; i < b1; i++) + getResults[i] = serialRead(s); + + stmWaitAck(s, STM_RETRIES_LONG); + printf("Received commands.\n"); + + + // send GET VERSION command + do { + c = getResults[1]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + b1 = serialRead(s); + b2 = serialRead(s); + b3 = serialRead(s); + stmWaitAck(s, STM_RETRIES_LONG); + printf("STM Bootloader version: %d.%d\n", (b1 & 0xf0) >> 4, (b1 & 0x0f)); + + // send GET ID command + do { + c = getResults[2]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + n = serialRead(s); + printf("STM Device ID: 0x"); + for (i = 0; i <= n; i++) { + b1 = serialRead(s); + printf("%02x", b1); + } + stmWaitAck(s, STM_RETRIES_LONG); + printf("\n"); + +/* + flash_size: + // read Flash size + c = getResults[3]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + + // if read not allowed, unprotect (which also erases) + if (!stmWaitAck(s, STM_RETRIES_LONG)) { + // unprotect command + do { + c = getResults[10]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + + // wait for results + if (stmWaitAck(s, STM_RETRIES_LONG)) + goto top; + } + + // send address + if (!stmWrite(s, "1FFFF7E0")) + goto flash_size; + + // send # bytes (N-1 = 1) + if (!stmWrite(s, "01")) + goto flash_size; + + b1 = serialRead(s); + b2 = serialRead(s); + printf("STM Flash Size: %dKB\n", b2<<8 | b1); +*/ + + // erase flash + erase_flash: + printf("Global flash erase [command 0x%x]...", getResults[6]); fflush(stdout); + do { + c = getResults[6]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + + // global erase + if (getResults[6] == 0x44) { + // mass erase + if (!stmWrite(s, "FFFF")) + goto erase_flash; + } + else { + c = 0xff; + serialWrite(s, &c, 1); + c = 0x00; + serialWrite(s, &c, 1); + + if (!stmWaitAck(s, STM_RETRIES_LONG)) + goto erase_flash; + } + + printf("Done.\n"); + + // upload hex file + printf("Flashing device...\n"); + jumpAddress = stmHexLoader(s, fp); + if (jumpAddress) { + printf("\nFlash complete, cycle power\n"); + + go: + // send GO command + do { + c = getResults[4]; + serialWrite(s, &c, 1); + c = 0xff ^ c; + serialWrite(s, &c, 1); + } while (!stmWaitAck(s, STM_RETRIES_LONG)); + + // send address + if (!stmWrite(s, jumpAddress)) + goto go; + } + else { + printf("\nFlash complete.\n"); + } +} diff --git a/src/baseflight/support/stmloader/stmbootloader.h b/src/baseflight/support/stmloader/stmbootloader.h new file mode 100644 index 0000000000..89a1b6bd1e --- /dev/null +++ b/src/baseflight/support/stmloader/stmbootloader.h @@ -0,0 +1,27 @@ +/* + This file is part of AutoQuad. + + AutoQuad is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + AutoQuad is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + You should have received a copy of the GNU General Public License + along with AutoQuad. If not, see . + + Copyright © 2011 Bill Nesbitt +*/ + +#ifndef _stmbootloader_h +#define _stmbootloader_h + +#include +#include "serial.h" + +extern void stmLoader(serialStruct_t *s, FILE *fp, unsigned char overrideParity); + +#endif