diff --git a/Backup of Fly.ewd b/Backup of Fly.ewd new file mode 100644 index 0000000..460d71a --- /dev/null +++ b/Backup of Fly.ewd @@ -0,0 +1,3276 @@ + + + 4 + + Debug + + ARM + + 1 + + C-SPY + 2 + + 33 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 1 + + + + + + + + CADI_ID + 2 + + 0 + 1 + 1 + + + + + + + + + CMSISDAP_ID + 2 + + 4 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + E2_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + + GPLINK_ID + 2 + + 0 + 1 + 1 + + + + + + + IJET_ID + 2 + + 9 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + JLINK_ID + 2 + + 16 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 3 + 1 + 1 + + + + + + + + + + + + + NULINK_ID + 2 + + 0 + 1 + 1 + + + + + + + PEMICRO_ID + 2 + + 3 + 1 + 1 + + + + + + + + STLINK_ID + 2 + + 8 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 1 + + + + + + + + TIFET_ID + 2 + + 1 + 1 + 1 + + + + + + + + + + + + + + + + + + + XDS100_ID + 2 + + 9 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\Azure\AzureArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\FreeRtos\FreeRtosArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin2.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SMX\smxAwareIarArm9a.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin + 0 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\TargetAccessServer\TargetAccessServer.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin + 0 + + + + + Release + + ARM + + 0 + + C-SPY + 2 + + 33 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 0 + + + + + + + + CADI_ID + 2 + + 0 + 1 + 0 + + + + + + + + + CMSISDAP_ID + 2 + + 4 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + E2_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + + GPLINK_ID + 2 + + 0 + 1 + 0 + + + + + + + IJET_ID + 2 + + 9 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + JLINK_ID + 2 + + 16 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 3 + 1 + 0 + + + + + + + + + + + + + NULINK_ID + 2 + + 0 + 1 + 0 + + + + + + + PEMICRO_ID + 2 + + 3 + 1 + 0 + + + + + + + + STLINK_ID + 2 + + 8 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 0 + + + + + + + + TIFET_ID + 2 + + 1 + 1 + 0 + + + + + + + + + + + + + + + + + + + XDS100_ID + 2 + + 9 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\Azure\AzureArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\FreeRtos\FreeRtosArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin2.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SMX\smxAwareIarArm9a.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin + 0 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\TargetAccessServer\TargetAccessServer.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin + 0 + + + + diff --git a/Backup of Fly.ewp b/Backup of Fly.ewp new file mode 100644 index 0000000..c2e1dc3 --- /dev/null +++ b/Backup of Fly.ewp @@ -0,0 +1,2528 @@ + + + 4 + + Debug + + ARM + + 1 + + General + 3 + + 36 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 38 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 12 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 1 + + + + + + + + + CUSTOM + 3 + + + + 0 + inputOutputBased + + + + ILINK + 0 + + 27 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 1 + + + + + + + BUILDACTION + 2 + + + + + Release + + ARM + + 0 + + General + 3 + + 36 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 38 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 12 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 0 + + + + + + + + + CUSTOM + 3 + + + + 0 + inputOutputBased + + + + ILINK + 0 + + 27 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 0 + + + + + + + BUILDACTION + 2 + + + + + dev + + $PROJ_DIR$\dev\bar.cpp + + + $PROJ_DIR$\dev\bar.h + + + $PROJ_DIR$\dev\eep.cpp + + + $PROJ_DIR$\dev\eep.h + + + $PROJ_DIR$\dev\imu.cpp + + + $PROJ_DIR$\dev\imu.h + + + $PROJ_DIR$\dev\led.cpp + + + $PROJ_DIR$\dev\led.h + + + + drv + + $PROJ_DIR$\drv\gpio.cpp + + + $PROJ_DIR$\drv\gpio.h + + + $PROJ_DIR$\drv\i2c.cpp + + + $PROJ_DIR$\drv\i2c.h + + + $PROJ_DIR$\drv\tick.cpp + + + $PROJ_DIR$\drv\tick.h + + + $PROJ_DIR$\drv\uart.cpp + + + $PROJ_DIR$\drv\uart.h + + + + utils + + $PROJ_DIR$\utils\med.cpp + + + $PROJ_DIR$\utils\med.h + + + $PROJ_DIR$\utils\med2.cpp + + Debug + + + + $PROJ_DIR$\utils\med2.h + + Debug + + + + $PROJ_DIR$\utils\pid.cpp + + + $PROJ_DIR$\utils\pid.h + + + + $PROJ_DIR$\main.cpp + + + $PROJ_DIR$\startup_stm32g431xx.s + + + $PROJ_DIR$\stm32g431xx.h + + + $PROJ_DIR$\stm32g431xx_flash.icf + + + $PROJ_DIR$\stm32g431xx_sram.icf + + + $PROJ_DIR$\system_stm32g4xx.c + + Debug + + ICCARM + + 38 + 0 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $PROJ_DIR$\system_stm32g4xx.h + + diff --git a/Backup of Fly.ewt b/Backup of Fly.ewt new file mode 100644 index 0000000..cec9dad --- /dev/null +++ b/Backup of Fly.ewt @@ -0,0 +1,3019 @@ + + + 4 + + Debug + + ARM + + 1 + + C-STAT + 518 + + 518 + + 0 + + 1 + 600 + 1 + 16 + 0 + 1 + 100 + Debug/C-STAT + + + 2.6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + RuntimeChecking + 0 + + 2 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + Release + + ARM + + 0 + + C-STAT + 518 + + 518 + + 0 + + 1 + 600 + 1 + 16 + 0 + 1 + 100 + Release/C-STAT + + + 2.6.0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + RuntimeChecking + 0 + + 2 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + dev + + $PROJ_DIR$\dev\bar.cpp + + + $PROJ_DIR$\dev\bar.h + + + $PROJ_DIR$\dev\eep.cpp + + + $PROJ_DIR$\dev\eep.h + + + $PROJ_DIR$\dev\imu.cpp + + + $PROJ_DIR$\dev\imu.h + + + $PROJ_DIR$\dev\led.cpp + + + $PROJ_DIR$\dev\led.h + + + + drv + + $PROJ_DIR$\drv\gpio.cpp + + + $PROJ_DIR$\drv\gpio.h + + + $PROJ_DIR$\drv\i2c.cpp + + + $PROJ_DIR$\drv\i2c.h + + + $PROJ_DIR$\drv\tick.cpp + + + $PROJ_DIR$\drv\tick.h + + + $PROJ_DIR$\drv\uart.cpp + + + $PROJ_DIR$\drv\uart.h + + + + utils + + $PROJ_DIR$\utils\med.cpp + + + $PROJ_DIR$\utils\med.h + + + $PROJ_DIR$\utils\med2.cpp + + + $PROJ_DIR$\utils\med2.h + + + $PROJ_DIR$\utils\pid.cpp + + + $PROJ_DIR$\utils\pid.h + + + + $PROJ_DIR$\main.cpp + + + $PROJ_DIR$\startup_stm32g431xx.s + + + $PROJ_DIR$\stm32g431xx.h + + + $PROJ_DIR$\stm32g431xx_flash.icf + + + $PROJ_DIR$\stm32g431xx_sram.icf + + + $PROJ_DIR$\system_stm32g4xx.c + + Debug + + + + $PROJ_DIR$\system_stm32g4xx.h + + diff --git a/Fly.ewd b/Fly.ewd new file mode 100644 index 0000000..227ea3e --- /dev/null +++ b/Fly.ewd @@ -0,0 +1,3284 @@ + + + 4 + + Debug + + ARM + + 1 + + C-SPY + 2 + + 33 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 1 + + + + + + + + CADI_ID + 2 + + 0 + 1 + 1 + + + + + + + + + CMSISDAP_ID + 2 + + 4 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + E2_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + + GPLINK_ID + 2 + + 0 + 1 + 1 + + + + + + + IJET_ID + 2 + + 10 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + JLINK_ID + 2 + + 16 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 3 + 1 + 1 + + + + + + + + + + + + + NULINK_ID + 2 + + 0 + 1 + 1 + + + + + + + PEMICRO_ID + 2 + + 3 + 1 + 1 + + + + + + + + STLINK_ID + 2 + + 8 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 1 + + + + + + + + TIFET_ID + 2 + + 1 + 1 + 1 + + + + + + + + + + + + + + + + + + + XDS100_ID + 2 + + 9 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\Azure\AzureArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\FreeRtos\FreeRtosArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin2.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SMX\smxAwareIarArm9a.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin + 0 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\TargetAccessServer\TargetAccessServer.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin + 0 + + + + + Release + + ARM + + 0 + + C-SPY + 2 + + 33 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 0 + + + + + + + + CADI_ID + 2 + + 0 + 1 + 0 + + + + + + + + + CMSISDAP_ID + 2 + + 4 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + E2_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + + GPLINK_ID + 2 + + 0 + 1 + 0 + + + + + + + IJET_ID + 2 + + 10 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + JLINK_ID + 2 + + 16 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 3 + 1 + 0 + + + + + + + + + + + + + NULINK_ID + 2 + + 0 + 1 + 0 + + + + + + + PEMICRO_ID + 2 + + 3 + 1 + 0 + + + + + + + + STLINK_ID + 2 + + 8 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 0 + + + + + + + + TIFET_ID + 2 + + 1 + 1 + 0 + + + + + + + + + + + + + + + + + + + XDS100_ID + 2 + + 9 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\Azure\AzureArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\FreeRtos\FreeRtosArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\Mbed\MbedArmPlugin2.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\SMX\smxAwareIarArm9a.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-286-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-III\uCOS-III-KA-CSpy.ewplugin + 0 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\TargetAccessServer\TargetAccessServer.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\uCProbe\uCProbePlugin.ENU.ewplugin + 0 + + + + diff --git a/Fly.ewp b/Fly.ewp new file mode 100644 index 0000000..3e40072 --- /dev/null +++ b/Fly.ewp @@ -0,0 +1,2665 @@ + + + 4 + + Debug + + ARM + + 1 + + General + 3 + + 37 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 39 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 12 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 1 + + + + + + + + + CUSTOM + 4 + + + + inputOutputBased + + + + ILINK + 0 + + 28 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 1 + + + + + + + BUILDACTION + 2 + + + + + Release + + ARM + + 0 + + General + 3 + + 37 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 39 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 12 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 0 + + + + + + + + + CUSTOM + 4 + + + + inputOutputBased + + + + ILINK + 0 + + 28 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 0 + + + + + + + BUILDACTION + 2 + + + + + dev + + $PROJ_DIR$\dev\bar.cpp + + + $PROJ_DIR$\dev\bar.h + + + $PROJ_DIR$\dev\com.cpp + + + $PROJ_DIR$\dev\com.h + + + $PROJ_DIR$\dev\eep.cpp + + + $PROJ_DIR$\dev\eep.h + + + $PROJ_DIR$\dev\flow.cpp + + + $PROJ_DIR$\dev\flow.h + + + $PROJ_DIR$\dev\gps.cpp + + + $PROJ_DIR$\dev\gps.h + + + $PROJ_DIR$\dev\imu.cpp + + + $PROJ_DIR$\dev\imu.h + + + $PROJ_DIR$\dev\laser.cpp + + + $PROJ_DIR$\dev\laser.h + + + $PROJ_DIR$\dev\led.cpp + + + $PROJ_DIR$\dev\led.h + + + $PROJ_DIR$\dev\ori.cpp + + + $PROJ_DIR$\dev\ori.h + + + $PROJ_DIR$\dev\sbus.cpp + + + $PROJ_DIR$\dev\sbus.h + + + $PROJ_DIR$\dev\tele.cpp + + + $PROJ_DIR$\dev\tele.h + + + + drv + + $PROJ_DIR$\drv\gpio.cpp + + + $PROJ_DIR$\drv\gpio.h + + + $PROJ_DIR$\drv\i2c.cpp + + + $PROJ_DIR$\drv\i2c.h + + + $PROJ_DIR$\drv\iwdg.cpp + + + $PROJ_DIR$\drv\iwdg.h + + + $PROJ_DIR$\drv\pwm.cpp + + + $PROJ_DIR$\drv\pwm.h + + + $PROJ_DIR$\drv\spi.cpp + + + $PROJ_DIR$\drv\spi.h + + + $PROJ_DIR$\drv\tick.cpp + + + $PROJ_DIR$\drv\tick.h + + + $PROJ_DIR$\drv\tim.cpp + + + $PROJ_DIR$\drv\tim.h + + + $PROJ_DIR$\drv\uart.cpp + + + $PROJ_DIR$\drv\uart.h + + + $PROJ_DIR$\drv\vl53l0x.cpp + + + $PROJ_DIR$\drv\vl53l0x.h + + + + utils + + $PROJ_DIR$\utils\filt.cpp + + + $PROJ_DIR$\utils\filt.h + + + $PROJ_DIR$\utils\med.cpp + + + $PROJ_DIR$\utils\med.h + + + $PROJ_DIR$\utils\med2.cpp + + + $PROJ_DIR$\utils\med2.h + + + $PROJ_DIR$\utils\mot.cpp + + + $PROJ_DIR$\utils\mot.h + + + $PROJ_DIR$\utils\move.cpp + + + $PROJ_DIR$\utils\move.h + + + $PROJ_DIR$\utils\pid.cpp + + + $PROJ_DIR$\utils\pid.h + + + $PROJ_DIR$\utils\prot.cpp + + + $PROJ_DIR$\utils\prot.h + + + $PROJ_DIR$\utils\prot_head.h + + + $PROJ_DIR$\utils\quat.cpp + + + $PROJ_DIR$\utils\quat.h + + + + $PROJ_DIR$\main.cpp + + + $PROJ_DIR$\startup_stm32g431xx.s + + + $PROJ_DIR$\stm32g431xx.h + + + $PROJ_DIR$\stm32g431xx_flash.icf + + + $PROJ_DIR$\stm32g431xx_sram.icf + + + $PROJ_DIR$\system_stm32g4xx.c + + Debug + + ICCARM + + 39 + 0 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $PROJ_DIR$\system_stm32g4xx.h + + diff --git a/Fly.ewt b/Fly.ewt new file mode 100644 index 0000000..2daadf9 --- /dev/null +++ b/Fly.ewt @@ -0,0 +1,3136 @@ + + + 4 + + Debug + + ARM + + 1 + + C-STAT + 519 + + 519 + + 0 + + 1 + 600 + 1 + 16 + 0 + 1 + 100 + Debug/C-STAT + + + 2.7.2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + RuntimeChecking + 0 + + 2 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + Release + + ARM + + 0 + + C-STAT + 519 + + 519 + + 0 + + 1 + 600 + 1 + 16 + 0 + 1 + 100 + Release/C-STAT + + + 2.7.2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + RuntimeChecking + 0 + + 2 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + dev + + $PROJ_DIR$\dev\bar.cpp + + + $PROJ_DIR$\dev\bar.h + + + $PROJ_DIR$\dev\com.cpp + + + $PROJ_DIR$\dev\com.h + + + $PROJ_DIR$\dev\eep.cpp + + + $PROJ_DIR$\dev\eep.h + + + $PROJ_DIR$\dev\flow.cpp + + + $PROJ_DIR$\dev\flow.h + + + $PROJ_DIR$\dev\gps.cpp + + + $PROJ_DIR$\dev\gps.h + + + $PROJ_DIR$\dev\imu.cpp + + + $PROJ_DIR$\dev\imu.h + + + $PROJ_DIR$\dev\laser.cpp + + + $PROJ_DIR$\dev\laser.h + + + $PROJ_DIR$\dev\led.cpp + + + $PROJ_DIR$\dev\led.h + + + $PROJ_DIR$\dev\ori.cpp + + + $PROJ_DIR$\dev\ori.h + + + $PROJ_DIR$\dev\sbus.cpp + + + $PROJ_DIR$\dev\sbus.h + + + $PROJ_DIR$\dev\tele.cpp + + + $PROJ_DIR$\dev\tele.h + + + + drv + + $PROJ_DIR$\drv\gpio.cpp + + + $PROJ_DIR$\drv\gpio.h + + + $PROJ_DIR$\drv\i2c.cpp + + + $PROJ_DIR$\drv\i2c.h + + + $PROJ_DIR$\drv\iwdg.cpp + + + $PROJ_DIR$\drv\iwdg.h + + + $PROJ_DIR$\drv\pwm.cpp + + + $PROJ_DIR$\drv\pwm.h + + + $PROJ_DIR$\drv\spi.cpp + + + $PROJ_DIR$\drv\spi.h + + + $PROJ_DIR$\drv\tick.cpp + + + $PROJ_DIR$\drv\tick.h + + + $PROJ_DIR$\drv\tim.cpp + + + $PROJ_DIR$\drv\tim.h + + + $PROJ_DIR$\drv\uart.cpp + + + $PROJ_DIR$\drv\uart.h + + + $PROJ_DIR$\drv\vl53l0x.cpp + + + $PROJ_DIR$\drv\vl53l0x.h + + + + utils + + $PROJ_DIR$\utils\filt.cpp + + + $PROJ_DIR$\utils\filt.h + + + $PROJ_DIR$\utils\med.cpp + + + $PROJ_DIR$\utils\med.h + + + $PROJ_DIR$\utils\med2.cpp + + + $PROJ_DIR$\utils\med2.h + + + $PROJ_DIR$\utils\mot.cpp + + + $PROJ_DIR$\utils\mot.h + + + $PROJ_DIR$\utils\move.cpp + + + $PROJ_DIR$\utils\move.h + + + $PROJ_DIR$\utils\pid.cpp + + + $PROJ_DIR$\utils\pid.h + + + $PROJ_DIR$\utils\prot.cpp + + + $PROJ_DIR$\utils\prot.h + + + $PROJ_DIR$\utils\prot_head.h + + + $PROJ_DIR$\utils\quat.cpp + + + $PROJ_DIR$\utils\quat.h + + + + $PROJ_DIR$\main.cpp + + + $PROJ_DIR$\startup_stm32g431xx.s + + + $PROJ_DIR$\stm32g431xx.h + + + $PROJ_DIR$\stm32g431xx_flash.icf + + + $PROJ_DIR$\stm32g431xx_sram.icf + + + $PROJ_DIR$\system_stm32g4xx.c + + Debug + + + + $PROJ_DIR$\system_stm32g4xx.h + + diff --git a/Fly.eww b/Fly.eww new file mode 100644 index 0000000..cdaf474 --- /dev/null +++ b/Fly.eww @@ -0,0 +1,7 @@ + + + + $WS_DIR$\Fly.ewp + + + diff --git a/Graph/Tele.slx b/Graph/Tele.slx new file mode 100644 index 0000000..304cb32 Binary files /dev/null and b/Graph/Tele.slx differ diff --git a/dev/bar.cpp b/dev/bar.cpp new file mode 100644 index 0000000..39f029b --- /dev/null +++ b/dev/bar.cpp @@ -0,0 +1,85 @@ +#include + +#include "i2c.h" + +#include "bar.h" + +static const unsigned char BAR_Addr = 0x5C; // LPS22HH + +void (*BAR_DoneProc)(BAR_Data& Data); + +float BAR_GetAltitude(float p0, float p1) +{ + return 44330.0f*(1.0f-powf(p1/p0, 1.0f/5.255f)); +} +//------------------------------------------------------------------------------ + +static inline void BAR_SetReg(unsigned char Reg, unsigned char Value) +{ + unsigned char reg[2]; + reg[0]=Reg; reg[1]=Value; + I2C2_Write(BAR_Addr, reg, 2); + //I2C2_Stop(); +} +//------------------------------------------------------------------------------ + +void BAR_Init() +{ + I2C2_Init(); + + BAR_SetReg(0x10, 0x3E); // RESET + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } +} +//------------------------------------------------------------------------------ + +float BAR_GetData(float* Temp) +{ + static float bar=0; + static float temp=0; + + unsigned char st; + I2C2_Write(BAR_Addr, 0x27); + I2C2_Read(BAR_Addr, &st, 1); + I2C2_Stop(); + + if(st & 1) + { + unsigned char reg[3]; + I2C2_Write(BAR_Addr, 0x28); + I2C2_Read(BAR_Addr, reg, sizeof(reg)); + I2C2_Stop(); + + + unsigned long b; + + b = reg[2]; + b = (b * 256U) + reg[1]; + b = (b * 256U) + reg[0]; + b *= 256U; + + bar=((float)b)/1048576.0f; + } + + if(st & 2) + { + unsigned char reg[2]; + I2C2_Write(BAR_Addr, 0x2B); + I2C2_Read(BAR_Addr, reg, sizeof(reg)); + I2C2_Stop(); + + + short t; + + t = (short)reg[1]; + t = (t * 256) + (short)reg[0]; + + temp = (float) t / 100.0f; + } + + *Temp=temp; + + return bar; + +} +//------------------------------------------------------------------------------ diff --git a/dev/bar.h b/dev/bar.h new file mode 100644 index 0000000..34f89c1 --- /dev/null +++ b/dev/bar.h @@ -0,0 +1,13 @@ +#pragma once + +struct BAR_Data +{ + long Temp; + float Pressure; +}; + +void BAR_Init(); + +float BAR_GetData(float* Temp); +void BAR_GetAsunc(void (*DoneProc)(BAR_Data& Data)); +float BAR_GetAltitude(float p0, float p1); diff --git a/dev/com.cpp b/dev/com.cpp new file mode 100644 index 0000000..24c0c6d --- /dev/null +++ b/dev/com.cpp @@ -0,0 +1,97 @@ +#include + +#include "uart.h" +#include "tick.h" + +#include "com.h" + +enum class MESSAGES_ID : unsigned char +{ + SysInfo = 1, + GyroInfo = 2, + AccelInfo = 3, + GpsInfo = 4, + InertialInfo = 5, + BatteryInfo = 6, + Ack = 7, + StatusCommand = 8, + StatusAllCommands = 9, + Command = 10, + RequestReg = 11, + ResponseReg = 12, + Auth = 13, + OpenKey = 14, + MissionCount = 15, + MissionItem = 16, + MissionItemAck = 17, + MissionRequestItem = 18, + RequestLastMessage = 19, + ConnectionTest = 20, + + CountMenuCategories = 32, + CategoriesMenu = 33, + CategoriesParameters = 34, +}; + +enum class COMMANDS_NAME : unsigned char +{ + ChangeNav = 1, + ChangeSpeed = 2, + Land = 3, + GoHome = 4, + StopEngine = 5, + StartEngine = 6, + Pause = 7, + Continue = 8, + GoToGlobal = 9, + GoToLocal = 10, + + SetParameter = 15, +}; + +enum class ERROR_CODE_COMMAND : unsigned char +{ + NoError = 0, +}; + +#pragma pack(push,1) + +struct HeaderBegin +{ + unsigned char stx = 0xAA; + unsigned short len1; + unsigned short len2; + unsigned char crc; + unsigned char data[0]; + + bool CheckCRC() + { + if(len1!=len2) return false; + unsigned char test = 0; + for (unsigned short a = 0; a < len1; a++) test ^= data[a]; + return crc==test; + } +}; + +struct HeaderMessages +{ + MESSAGES_ID msgId; + unsigned char srcId; + unsigned char dstId; + unsigned char len; + unsigned char data[0]; + + +}; + +#pragma pack(pop) + +//void TELE_Init() +//{ +// UART2_Init(57600); +//} +// +//void TELE_Update(const void* info, unsigned long size, unsigned long update) +//{ +// +//} diff --git a/dev/com.h b/dev/com.h new file mode 100644 index 0000000..6208db5 --- /dev/null +++ b/dev/com.h @@ -0,0 +1,4 @@ +#pragma once + +void COM_Init(); +void COM_Update(); diff --git a/dev/eep.cpp b/dev/eep.cpp new file mode 100644 index 0000000..7ea76e9 --- /dev/null +++ b/dev/eep.cpp @@ -0,0 +1,35 @@ +#include "i2c.h" + +#include "eep.h" + +static const unsigned char EEP_Addr = 0x50; // AT24C256 + +static inline short Rev16(short v) +{ + asm("REV16 %1, %0" : "=r" (v) : "r" (v)); // v = v<<8 | v>>8; + return v; +} +//------------------------------------------------------------------------------ + +void EEP_Init() // AT24C256 +{ + I2C1_Init(); +} +//------------------------------------------------------------------------------ + +void EEP_Read(unsigned short Addr, void* Data, unsigned short Size) +{ + Addr=Rev16(Addr); + I2C1_Write(EEP_Addr, &Addr, 2); + I2C1_Read(EEP_Addr, Data, Size); + I2C1_Stop(); +} +//------------------------------------------------------------------------------ + +void EEP_Write(unsigned short Addr, const void* Data, unsigned short Size) +{ + Addr=Rev16(Addr); + I2C1_Write2(EEP_Addr, &Addr, 2, Data, Size); + I2C1_Stop(); +} +//------------------------------------------------------------------------------ diff --git a/dev/eep.h b/dev/eep.h new file mode 100644 index 0000000..b7e636e --- /dev/null +++ b/dev/eep.h @@ -0,0 +1,6 @@ +#pragma once + +void EEP_Init(); + +void EEP_Read(unsigned short Addr, void* Data, unsigned short Size); +void EEP_Write(unsigned short Addr, const void* Data, unsigned short Size); diff --git a/dev/flow.cpp b/dev/flow.cpp new file mode 100644 index 0000000..4286f60 --- /dev/null +++ b/dev/flow.cpp @@ -0,0 +1,131 @@ +#include +#include + +#include "gpio.h" + +#include "spi.h" +#include "tick.h" + +#include "laser.h" + +static void WriteReg(char reg, char value) +{ + char send[2]={reg | 0x80, value}; + SPI2_TransferCons(send, 2, 0, 0); +} + +bool FLOW_Init() // PMW3901 +{ + SPI2_Init(); + + WriteReg(0x3A, 0x5A); + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } + + // Test the SPI communication, checking chipId and inverse chipId + + char reg[4]={0x00, 0, 0x5F, 0}; + char result[4]={0, 0,0,0}; + SPI2_TransferParallel(reg, result, 4); + + if (result[1] != 0x49 || result[3] != 0xB6) return false; + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } + + WriteReg(0x7F, 0x00); + WriteReg(0x61, 0xAD); + WriteReg(0x7F, 0x03); + WriteReg(0x40, 0x00); + WriteReg(0x7F, 0x05); + WriteReg(0x41, 0xB3); + WriteReg(0x43, 0xF1); + WriteReg(0x45, 0x14); + WriteReg(0x5B, 0x32); + WriteReg(0x5F, 0x34); + WriteReg(0x7B, 0x08); + WriteReg(0x7F, 0x06); + WriteReg(0x44, 0x1B); + WriteReg(0x40, 0xBF); + WriteReg(0x4E, 0x3F); + + WriteReg(0x7F, 0x08); + WriteReg(0x65, 0x20); + WriteReg(0x6A, 0x18); + WriteReg(0x7F, 0x09); + WriteReg(0x4F, 0xAF); + WriteReg(0x5F, 0x40); + WriteReg(0x48, 0x80); + WriteReg(0x49, 0x80); + WriteReg(0x57, 0x77); + WriteReg(0x60, 0x78); + WriteReg(0x61, 0x78); + WriteReg(0x62, 0x08); + WriteReg(0x63, 0x50); + WriteReg(0x7F, 0x0A); + WriteReg(0x45, 0x60); + WriteReg(0x7F, 0x00); + WriteReg(0x4D, 0x11); + WriteReg(0x55, 0x80); + WriteReg(0x74, 0x1F); + WriteReg(0x75, 0x1F); + WriteReg(0x4A, 0x78); + WriteReg(0x4B, 0x78); + WriteReg(0x44, 0x08); + WriteReg(0x45, 0x50); + WriteReg(0x64, 0xFF); + WriteReg(0x65, 0x1F); + WriteReg(0x7F, 0x14); + WriteReg(0x65, 0x60); + WriteReg(0x66, 0x08); + WriteReg(0x63, 0x78); + WriteReg(0x7F, 0x15); + WriteReg(0x48, 0x58); + WriteReg(0x7F, 0x07); + WriteReg(0x41, 0x0D); + WriteReg(0x43, 0x14); + WriteReg(0x4B, 0x0E); + WriteReg(0x45, 0x0F); + WriteReg(0x44, 0x42); + WriteReg(0x4C, 0x80); + WriteReg(0x7F, 0x10); + WriteReg(0x5B, 0x02); + WriteReg(0x7F, 0x07); + WriteReg(0x40, 0x41); + WriteReg(0x70, 0x00); + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } + + WriteReg(0x32, 0x44); + WriteReg(0x7F, 0x07); + WriteReg(0x40, 0x40); + WriteReg(0x7F, 0x06); + WriteReg(0x62, 0xf0); + WriteReg(0x63, 0x00); + WriteReg(0x7F, 0x0D); + WriteReg(0x48, 0xC0); + WriteReg(0x6F, 0xd5); + WriteReg(0x7F, 0x00); + WriteReg(0x5B, 0xa0); + WriteReg(0x4E, 0xA8); + WriteReg(0x5A, 0x50); + WriteReg(0x40, 0x80); + + return true; +} + +bool FLOW_GetMotion(short* dX, short* dY, unsigned char* qual) +{ + char reg[12]={0x02, 0, 0x03, 0, 0x04, 0, 0x05, 0, 0x06, 0, 0x07, 0}; + + SPI2_TransferParallel(reg, reg, 12); + + short x = ((short)reg[5] << 8) | reg[3]; + short y = ((short)reg[9] << 8) | reg[7]; + + if(dX) *dX = x; + if(dY) *dY = y; + + if(qual) *qual = reg[11]; + + return reg[1] & 0x80; +} diff --git a/dev/flow.h b/dev/flow.h new file mode 100644 index 0000000..52f76d7 --- /dev/null +++ b/dev/flow.h @@ -0,0 +1,4 @@ +#pragma once + +bool FLOW_Init(); +bool FLOW_GetMotion(short* dX, short* dY, unsigned char* qual); diff --git a/dev/gps.cpp b/dev/gps.cpp new file mode 100644 index 0000000..fd72d49 --- /dev/null +++ b/dev/gps.cpp @@ -0,0 +1,568 @@ +#include +#include +#include + +#include "gpio.h" + +#include "uart.h" +#include "tick.h" +#include "ori.h" + +#include "filt.h" + +#include "gps.h" + +//FilterGPS filt_x, filt_y, filt_z; + +/*void GPS_Navigation(bool valid, ORI_Data& data, float p[3]) +{ + filt_x.Update(valid, p[0], data.Iner.X/1000); + filt_y.Update(valid, p[1], data.Iner.Y/1000); + filt_z.Update(valid, p[2], data.Iner.Z/1000); + + data.Speed.X=filt_x.Speed.Value; + data.Speed.Y=filt_y.Speed.Value; + data.Speed.Z=filt_z.Speed.Value; + + data.Pos.X=filt_x.Position.Value; + data.Pos.Y=filt_y.Position.Value; + data.Pos.Z=filt_z.Position.Value; +}*/ +//------------------------------------------------------------------------------ + +float GPS_LocalDistance(Point p1, Point p2, float& dx, float& dy) // light formula +{ + const float pi = 3.14159265359f; + const float er = 6371000.0f; // Radius of the earth in m + + float lat = p1.Latitude - p2.Latitude; + float lon = p1.Longitude - p2.Longitude; + + float y = er/360.0f * (lat*pi*2.0f); // lat + dy = y; + + float l = ((float)(p1.Latitude + p2.Latitude)) / 2.0f; + float r = cosf(l*pi/180.0f) * er; + float x = r/360.0f * (lon*pi*2.0f); // long + dx = x; + + float d = sqrtf(x*x + y*y); + return d; +} +//------------------------------------------------------------------------------ + +float GPS_GlobalDistance(Point p1, Point p2) // Haversine formula +{ + const float pi = 3.14159265359f; + const float er = 6371000.0f; // Radius of the earth in m + + float dLat = ((float)(p2.Latitude - p1.Latitude))*pi/180.0f; + float dLon = ((float)(p2.Longitude - p1.Longitude))*pi/180.0f; + + float lat1 = p1.Latitude, lat2 = p2.Latitude; + + float sdlat=sinf(dLat/2.0f); + float sdlon=sinf(dLon/2.0f); + + float a = (sdlat*sdlat) + cosf((lat1)*pi/180.0f) * cosf((lat2)*pi/180.0f) * (sdlon*sdlon); + float c = 2.0f * atan2f(sqrtf(a), sqrtf(1.0f-a)); + float d = er * c; // Distance in m + return d; +} +//------------------------------------------------------------------------------ + +struct GPS_Head +{ + static const unsigned long Size = 7; + const char* NMEA; +}; + +struct GPS_GNRMC // $GNRMC,hhmmss.sss,A,ggmm.mm,P,gggmm.mm,J,v.v,b.b,ddmmyy,x.x,n,m*hh/r/n +{ + static constexpr GPS_Head Head = {"$GNRMC,"}; // Recommended minimum specific Transit data + //--- + char* Time; // UTC of position fix + char* Valid; // Data status (V=navigation receiver warning) + char* Latitude; // Latitude of fix + char* Pole; // N or S + char* Longitude; // Longitude of fix + char* J; // E or W + char* HorSpeed; // Speed over ground in knots + char* Angle; // Track made good in degrees True + char* Date; // UT date + char* Mag; // Magnetic variation degrees (Easterly var. subtracts from true course) + char* MagAng; // Magnetic declination direction, E (east) or W (west) + char* Mode; // Mode indication (A=autonomous positioning, D=differential, E=estimation, N=invalid data) + //--- + // Checksum +}; + +struct GPS_GNGGA // $GNGGA,hhmmss.ss,ggmm.mm,a,gggmm.mm,a,x,xx,x.x,x.x,M,x.x,M,x.x,xxxx*hh/r/n +{ + static constexpr GPS_Head Head = {"$GNGGA,"}; // Global Positioning System Fix Data + //--- + char* Time; // UTC of position + char* Latitude; // latitude of position + char* Pole; // N or S + char* Longitude; // Longitude of position + char* J; // E or W + char* Quality; // GPS Quality indicator (0=no fix, 1=GPS fix, 2=Dif. GPS fix) + char* Satellites; // Number of satellites in use [not those in view] + char* HDOP; // Horizontal dilution of position + char* Altitude; // Antenna altitude above/below mean sea level (geoid) + char* UnitsAlt; // Meters (Antenna height unit) + char* Geoidal; // Geoidal separation (Diff. between WGS-84 earth ellipsoid andmean sea level. -=geoid is below WGS-84 ellipsoid) + char* UnitsGeoidal; // Meters (Units of geoidal separation) + char* LastUpdate; // Age in seconds since last update from diff. reference station + char* StationID; // Diff. reference station ID# + //--- + // Checksum +}; + +struct GPS_GNGSA // $GNGSA,mode,fix,PRN(11),PDOP,HDOP,VDOP,*hh/r/n +{ + static constexpr GPS_Head Head = {"$GNGSA,"}; // Global Positioning System Fix Data + //--- + char* Mode; // M = Manual, A = Automatic + char* FixType; // 1 = not available, 2 = 2D, 3 = 3D + char* ID_1; // 01 to 32 for GPS, 33 to 64 for SBAS, 64+ for GLONASS + char* ID_2; + char* ID_3; + char* ID_4; + char* ID_5; + char* ID_6; + char* ID_7; + char* ID_8; + char* ID_9; + char* ID_10; + char* ID_11; + char* ID_12; + char* PDOP; + char* HDOP; + char* VDOP; + //--- + // Checksum +}; + +struct GPS_GPGSV // $GPGSV,count,index,visible,[ID,elevation,azimuth,SNR]*hh/r/n +{ + static constexpr GPS_Head Head = {"$GPGSV,"}; // Global Positioning System Fix Data + //--- + char* Count; // M = Manual, A = Automatic + char* Index; // 1 = not available, 2 = 2D, 3 = 3D + char* Visible; // 01 to 32 for GPS, 33 to 64 for SBAS, 64+ for GLONASS + + char* ID_1; + char* Elevation_1; + char* Azimuth_1; + char* SNR_1; + + char* ID_2; + char* Elevation_2; + char* Azimuth_2; + char* SNR_2; + + char* ID_3; + char* Elevation_3; + char* Azimuth_3; + char* SNR_3; + + char* ID_4; + char* Elevation_4; + char* Azimuth_4; + char* SNR_4; + + //--- + // Checksum +}; + +struct GPS_GLGSV // $GLGSV,count,index,visible,[ID,elevation,azimuth,SNR]*hh/r/n +{ + static constexpr GPS_Head Head = {"$GLGSV,"}; // Global Positioning System Fix Data + //--- + char* Count; // M = Manual, A = Automatic + char* Index; // 1 = not available, 2 = 2D, 3 = 3D + char* Visible; // 01 to 32 for GPS, 33 to 64 for SBAS, 64+ for GLONASS + + char* ID_1; + char* Elevation_1; + char* Azimuth_1; + char* SNR_1; + + char* ID_2; + char* Elevation_2; + char* Azimuth_2; + char* SNR_2; + + char* ID_3; + char* Elevation_3; + char* Azimuth_3; + char* SNR_3; + + char* ID_4; + char* Elevation_4; + char* Azimuth_4; + char* SNR_4; + + //--- + // Checksum +}; + +enum class GPS_PROTO {GNRMC, GNGGA, GNGSA, GPGSV, GLGSV, COUNT}; +static const long GPS_ProtCount = (long)GPS_PROTO::COUNT; +static GPS_Head GPS_Protocols[GPS_ProtCount] = { GPS_GNRMC::Head, GPS_GNGGA::Head, GPS_GNGSA::Head, GPS_GPGSV::Head, GPS_GLGSV::Head }; + +struct GPS_Info +{ + GPS_PROTO Type; + + static const unsigned long Length = 256; + char Data[Length]; + + static const unsigned long Count = 32; + char* Param[Count]; + + long Begin = 0; + long Index = 0; + long Size = 0; + + unsigned char CRC8; +}; + + +static GPS_Info Info; + +void (*GPS_CallBack)(GPS_PROTO Proto, void* Data)=0; + +//------------------------------------------------------------------------------------------------------------------------------ +/*static unsigned long UARTt_Recv(void* Data, unsigned long Size, bool WaitAll=false) // For Check ONLY !!!!!!!!!!!!!!!! +{ + static int begin=0; + + const char test[]="$GNGGA,122013.10,4719.45110,N,03846.54105,E,1,12,0.66,35.9,M,17.6,M,,*7A\r\n"; + unsigned long size=strlen(test); + + memcpy(Data, test, Size=size) begin=0; + + //return 1; + return size; +}*/ +//------------------------------------------------------------------------------------------------------------------------------ + +void GPS_Update() +{ + char* head = Info.Data; + + Info.Size += UART1_Recv(head + Info.Size, Info.Length - Info.Size); + + long size = Info.Size - Info.Index; + + while (size) + { + char* data = head + Info.Index; + + if (Info.Index && *data == '$') + { + memcpy(head, data, size); + Info.Index = 0; + Info.Begin = 0; + Info.Size = size; + data = head; + } + + if (!Info.Begin) + { + if (*head != '$') + { + Info.Index++; + size--; + continue; + } + //--- + if (Info.Size < GPS_Head::Size) return; + //--- + Info.Type = GPS_PROTO::COUNT; + for (long a = 0; a < GPS_ProtCount; a++) + { + const char* nmea = GPS_Protocols[a].NMEA; + if (memcmp(head, nmea, GPS_Head::Size) == 0) + { + Info.CRC8 = 0x0E; + for (long a = 0; nmea[a]; a++) Info.CRC8 ^= nmea[a]; + Info.Type = (GPS_PROTO)a; + break; + } + } + //--- + if (Info.Type == GPS_PROTO::COUNT) + { + Info.Index++; + *head = '#'; + size--; + continue; + } + //--- + Info.Index = GPS_Head::Size; + size = Info.Size - GPS_Head::Size; + //--- + Info.Param[Info.Begin++] = head + Info.Index; + //--- + continue; + } + //--- + if (Info.Size > Info.Length) + { + Info.Begin = 0; + Info.Index = 0; + Info.Size = 0; + return; + } + //--- + if (Info.Begin >= Info.Count) + { + if (*data == '\n') + { + *data = '\0'; + size--; + char* end; + unsigned char crc8 = strtol(data-3, &end, 16); + if ((end == data - 1) && (crc8 == Info.CRC8)) + { + if (GPS_CallBack) GPS_CallBack(Info.Type, Info.Param); + //--- + if (size) memcpy(Info.Data, data + 1, size); + } + //--- + Info.Begin = 0; + Info.Index = 0; + Info.Size = size; + //--- + continue; + } + } + else + { + Info.CRC8 ^= *data; + //--- + if (*data == ',') + { + *data = '\0'; + Info.Param[Info.Begin++] = ++data; + } + else if (*data == '*') + { + *data++ = '\0'; + while (Info.Begin < Info.Count) + { + Info.Param[Info.Begin++] = nullptr; + } + } + } + //--- + Info.Index++; + size--; + } + + if (!Info.Begin && Info.Index) + { + Info.Index = 0; + Info.Size = 0; + } +} +//------------------------------------------------------------------------------ + +static unsigned char GPS_VisibleGPS=0; +static unsigned char GPS_VisibleGLO=0; + +static unsigned char Base_Noise[256]; + +Point GetCoordinates_Coord; +bool GetCoordinates_Valid; +bool GetCoordinates_Update; + +Point Base_BeginXYZ; + +static float Base_Alt=0, Base_Geo=0; +static unsigned char Base_Used, Base_Fix; + +static GPS_BaseInfo GPS_BaseInfoData; + +static void GPS_CallBack_GSV(GPS_PROTO Proto, void* Data) +{ + if(Proto==GPS_PROTO::GNGGA) + { + GetCoordinates_Update=true; + + GPS_GNGGA* data=(GPS_GNGGA*)Data; + + GetCoordinates_Valid = (data->Quality[0] && (data->Quality[0]=='1' || data->Quality[0]=='2')); + + float geo=0; + if(data->Geoidal[0] && GetCoordinates_Valid) geo=strtof(data->Geoidal, 0); + + if(data->Altitude[0]) GetCoordinates_Coord.Altitude=strtof(data->Altitude, 0); + //--- + Base_Geo=GetCoordinates_Coord.Altitude+geo; + + + Base_Alt=Base_Geo-Base_BeginXYZ.Altitude; + //--- + GetCoordinates_Coord.Altitude+=geo; + + if(data->Latitude[0] && GetCoordinates_Valid) + { + GetCoordinates_Coord.Latitude=(data->Latitude[0]-'0')*10 + data->Latitude[1]-'0'; + GetCoordinates_Coord.Latitude+=strtod(data->Latitude+2, 0)/60; + } + //--- + if(data->Longitude[0] && GetCoordinates_Valid) + { + GetCoordinates_Coord.Longitude=(data->Longitude[0]-'0')*100 + (data->Longitude[1]-'0')*10 + data->Longitude[2]-'0'; + GetCoordinates_Coord.Longitude+=strtod(data->Longitude+3, 0)/60; + } + + if(data->Satellites[0] && GetCoordinates_Valid) Base_Used=strtoul(data->Satellites, 0, 10); + + if(data->Quality[0] && GetCoordinates_Valid) Base_Fix=strtoul(data->Quality, 0, 10); + } + + if(Proto==GPS_PROTO::GPGSV) + { + GPS_GPGSV* data=(GPS_GPGSV*)Data; + GPS_VisibleGPS = strtoul(data->Visible, 0, 10); + + if(!data->Index || *data->Index=='1') memset(Base_Noise, 0, sizeof(Base_Noise)); + + long id; + + if(data->ID_1) + { + id=strtoul(data->ID_1, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_1, 0, 10); + } + if(data->ID_2) + { + id=strtoul(data->ID_2, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_2, 0, 10); + } + if(data->ID_3) + { + id=strtoul(data->ID_3, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_3, 0, 10); + } + if(data->ID_4) + { + id=strtoul(data->ID_4, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_4, 0, 10); + } + } + else if(Proto==GPS_PROTO::GLGSV) + { + GPS_GLGSV* data=(GPS_GLGSV*)Data; + GPS_VisibleGLO = strtoul(data->Visible, 0, 10); + + long id; + + if(data->ID_1) + { + id=strtoul(data->ID_1, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_1, 0, 10); + } + if(data->ID_2) + { + id=strtoul(data->ID_2, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_2, 0, 10); + } + if(data->ID_3) + { + id=strtoul(data->ID_3, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_3, 0, 10); + } + if(data->ID_4) + { + id=strtoul(data->ID_4, 0, 10); + if(id<256) Base_Noise[id]=strtoul(data->SNR_4, 0, 10); + } + + if(*data->Count==*data->Index) + { + float noise=0, count=0; + for(long a=0; a<256; a++) + { + if(!Base_Noise[a]) continue; + noise+=Base_Noise[a]; + count++; + } + + if(count) GPS_BaseInfoData.noise=noise/count; + else GPS_BaseInfoData.noise=0; + + GPS_BaseInfoData.satVisible=GPS_VisibleGPS+GPS_VisibleGLO; + } + } + else if(Proto==GPS_PROTO::GNRMC) + { + GPS_GNRMC* data=(GPS_GNRMC*)Data; + + GPS_BaseInfoData.lat=GetCoordinates_Coord.Latitude; + GPS_BaseInfoData.lon=GetCoordinates_Coord.Longitude; + + if(data->HorSpeed[0]) GPS_BaseInfoData.speed=strtof(data->HorSpeed, 0); + + if(data->Time[0]) GPS_BaseInfoData.timeUTC=strtof(data->Time, 0); + + float dx, dy; + GPS_LocalDistance(Base_BeginXYZ, {GPS_BaseInfoData.lat, GPS_BaseInfoData.lon}, dx, dy); + + GPS_BaseInfoData.LocalXYZ[0]=dx; + GPS_BaseInfoData.LocalXYZ[1]=-dy; + GPS_BaseInfoData.LocalXYZ[2]=Base_Geo-Base_BeginXYZ.Altitude; + } + else if(Proto==GPS_PROTO::GNGSA) + { + GPS_GNGSA* data=(GPS_GNGSA*)Data; + + if(data->HDOP[0]) GPS_BaseInfoData.hdop=strtof(data->HDOP, 0); + if(data->VDOP[0]) GPS_BaseInfoData.vdop=strtof(data->VDOP, 0); + if(data->PDOP[0]) GPS_BaseInfoData.pdop=strtof(data->PDOP, 0); + } +} +//------------------------------------------------------------------------------ + +void GPS_Init() +{ + UART1_Init(230400); + GPS_CallBack=GPS_CallBack_GSV; + memset(Base_Noise, 0, sizeof(Base_Noise)); +} + +bool GPS_GetCoordinates(Point& Coord, bool& Valid) +{ + if(!GetCoordinates_Update) return false; + + GetCoordinates_Update=false; + + Coord=GetCoordinates_Coord; + Valid=GetCoordinates_Valid; + + return true; +} +//------------------------------------------------------------------------------ + +bool GPS_GetBaseInfo(GPS_BaseInfo& Info) +{ + Info=GPS_BaseInfoData; + + Info.realAlt=Base_Alt; + Info.absAlt=Base_Geo; + Info.satUsed=Base_Used; + Info.fixType=Base_Fix; + + return true; +} +//------------------------------------------------------------------------------ diff --git a/dev/gps.h b/dev/gps.h new file mode 100644 index 0000000..b90bf40 --- /dev/null +++ b/dev/gps.h @@ -0,0 +1,35 @@ +#pragma once + +struct Point { double Latitude; double Longitude; float Altitude; }; + +extern Point Base_BeginXYZ; + +void GPS_Navigation(bool valid, ORI_Data& data, float p[3]); + +float GPS_LocalDistance(Point p1, Point p2, float& dx, float& dy); // light formula +float GPS_GlobalDistance(Point p1, Point p2); // Haversine formula + +void GPS_Init(); +void GPS_Update(); +bool GPS_GetCoordinates(Point& Coord, bool& Valid); + +struct GPS_BaseInfo +{ + float LocalXYZ[3]; + float lat; + float lon; + float absAlt; + float realAlt; + float hdop; + float vdop; + float pdop; + float noise; + float jamming; // + unsigned char satVisible; + unsigned char satUsed; + float speed; + unsigned char fixType; // NO_GPS - 0, NO_FIX - 1, 2D_FIX - 2, 3D_FIX - 3, DGPS - 4, RTK_FLOAT - 5, RTK_FIXED - 6, STATIC - 7, PPP - 8 + unsigned long long timeUTC; +}; + +bool GPS_GetBaseInfo(GPS_BaseInfo& Info); diff --git a/dev/imu.cpp b/dev/imu.cpp new file mode 100644 index 0000000..0d60fa7 --- /dev/null +++ b/dev/imu.cpp @@ -0,0 +1,71 @@ +#include "i2c.h" + +#include "imu.h" + +static const unsigned char IMU_Addr = 0x6A; // ACC GYR + +static inline short Rev16(short v) +{ + asm("REV16 %1, %0" : "=r" (v) : "r" (v)); // v = v<<8 | v>>8; + return v; +} +//------------------------------------------------------------------------------ + +static inline void IMU_SetReg(unsigned char Reg, unsigned char Value) +{ + unsigned char reg[2]; + reg[0]=Reg; reg[1]=Value; + I2C2_Write(IMU_Addr, reg, 2); + I2C2_Stop(); +} +//------------------------------------------------------------------------------ + +static inline unsigned char IMU_GetReg(unsigned char Reg) +{ + I2C2_Write(IMU_Addr, Reg); + I2C2_Read(IMU_Addr, &Reg, 1); + I2C2_Stop(); + return Reg; +} +//------------------------------------------------------------------------------ + +void IMU_Init() +{ + I2C2_Init(); + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } + + unsigned char wai=IMU_GetReg(0x0F); + + IMU_SetReg(0x10, 0x38); + IMU_SetReg(0x11, 0x48); + IMU_SetReg(0x12, 0x06); + + + + for(int a=0; a<100000; a++) { asm volatile("NOP"); } +} +//------------------------------------------------------------------------------ + +void IMU_Get(IMU_Data& Data) +{ + struct {short temp; short gx; short gy; short gz; short ax; short ay; short az; } data; + + I2C2_Write(IMU_Addr, 0x20); + I2C2_Read(IMU_Addr, &data, sizeof(data)); + I2C2_Stop(); + + Data.Temp = 21+(((long)Rev16(data.temp))*128)/42735; // 21+(temperature / 333.87) + + + //------------------------------ imu perevernuta, x z inverse + Data.Acc.X = -Rev16(data.ax); + Data.Acc.Y = Rev16(data.ay); + Data.Acc.Z = -Rev16(data.az); + + Data.Gyr.X = -Rev16(data.gx); + Data.Gyr.Y = Rev16(data.gy); + Data.Gyr.Z = -Rev16(data.gz); + +} +//------------------------------------------------------------------------------ diff --git a/dev/imu.h b/dev/imu.h new file mode 100644 index 0000000..9c583d9 --- /dev/null +++ b/dev/imu.h @@ -0,0 +1,20 @@ +#pragma once + +struct IMU_Data +{ + short Temp; + struct { short X, Y, Z; } Acc; + struct { short X, Y, Z; } Gyr; + struct { short X, Y, Z; } Mag; + + float Bar; + float Tmp; +}; + +struct MAG_Data +{ + short X, Y, Z; +}; + +void IMU_Init(); +void IMU_Get(IMU_Data& Data); diff --git a/dev/laser.cpp b/dev/laser.cpp new file mode 100644 index 0000000..9159c76 --- /dev/null +++ b/dev/laser.cpp @@ -0,0 +1,54 @@ +#include "laser.h" +#include "i2c.h" +#include + +#include "vl53l0x.h" +#include "tick.h" + +#define ADDR_LASER 0x29 // VL53L0X +#define IDENTIFICATION_MODEL_ID 0xC0 + + + + + +unsigned char Laser_ReadReg(unsigned char reg) +{ + unsigned char val; + I2C1_Write(ADDR_LASER, reg); + I2C1_Read(ADDR_LASER, &val, 1); + I2C1_Stop(); + return val; +} + +unsigned char Laser_WriteReg(unsigned char reg, unsigned char reg2) +{ + unsigned char val; + I2C1_Write(ADDR_LASER, reg); + + I2C1_Write(ADDR_LASER, reg2); + I2C1_Stop(); + return val; +} + +VL53L0X sensor; + +bool Laser_Init_v2(void){ + I2C1_Init(); + bool fl = sensor.init(); + sensor.startContinuous(); + return fl; +} + +bool isRangeReady() +{ + return sensor.isRangeReady(); +} + + +uint16_t getRange() +{ + + return sensor.readRange(); +} + diff --git a/dev/laser.h b/dev/laser.h new file mode 100644 index 0000000..37512aa --- /dev/null +++ b/dev/laser.h @@ -0,0 +1,10 @@ + +#pragma once +#include + +bool Laser_Init(void); +short Laser_Read_mm(void); +bool Laser_Init_v2(void); +uint16_t getRange(); + +bool isRangeReady(); diff --git a/dev/led.cpp b/dev/led.cpp new file mode 100644 index 0000000..a427057 --- /dev/null +++ b/dev/led.cpp @@ -0,0 +1,20 @@ +#include "stm32g4xx.h" + +#include "gpio.h" + +#include "led.h" + +void LED_Init() +{ + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOAEN; + GPIO_InitPin(GPIO_PIN_15 | GPIO_PORT_A | GPIO_OUTPUT); + GPIO_InitPin(GPIO_PIN_14 | GPIO_PORT_B | GPIO_OUTPUT); +} +//------------------------------------------------------------------------------ + +void LED_Set(bool Set) +{ + if (Set) GPIOA->BSRR = GPIO_BSRR_BS_15; + else GPIOA->BSRR = GPIO_BSRR_BR_15; +} +//------------------------------------------------------------------------------ diff --git a/dev/led.h b/dev/led.h new file mode 100644 index 0000000..914066c --- /dev/null +++ b/dev/led.h @@ -0,0 +1,4 @@ +#pragma once + +void LED_Init(); +void LED_Set(bool Set); diff --git a/dev/ori.cpp b/dev/ori.cpp new file mode 100644 index 0000000..eca7a95 --- /dev/null +++ b/dev/ori.cpp @@ -0,0 +1,281 @@ +#include + +#include "imu.h" +#include "bar.h" + +#include "med2.h" + +#include "ori.h" +#include "quat.h" + +static const float PI = 3.14159265359f; +static const float TO_DEG = 180.0f/PI; +static const float TO_RAD = PI/180.0f; + +static float FK_PR = 0.01f; +static float FK_Y = 0.01f; + +static float MEGA_BAR; +static float MEGA_BAR_MIN=0.00001f; +static float MEGA_BAR_MAX=0.1f; +static float MEGA_BAR_MUL = 100.0f; +static float MEGA_BAR_POW = 2.0f; +static float MEGA_BAR_CNT = 7.0f; + +ORI_Data DataORI; + +const int BAR_MedCount=50; +long BAR_MedData[BAR_MedCount]; +unsigned char BAR_MedIndex[BAR_MedCount]; +MED2_Data BAR_Med = {BAR_MedCount, 0, BAR_MedIndex, BAR_MedData, 20}; + +static float MegaFilterAlt(const long Freq, const float Alt, float& Speed, float& Acc) +{ + static float falt=0; + falt=falt*(1.0f-MEGA_BAR)+(Alt)*MEGA_BAR; + + static float alt_speed=0, alt_acc=0; + static int count=0; + if(count>=MEGA_BAR_CNT) + { + static float last_b=0, last_s=0; + alt_speed=(falt-last_b)*Freq/MEGA_BAR_CNT; + alt_acc=(alt_speed-last_s); + last_b=falt; + last_s=alt_speed; + count=0; + } + else count++; + + float coef_w, coef_s; + + coef_w=MEGA_BAR_MIN; + float sub=fabsf(Alt-falt); + coef_w*=powf(sub*MEGA_BAR_MUL, MEGA_BAR_POW); + if(coef_w>MEGA_BAR_MAX) coef_w=MEGA_BAR_MAX; + if(coef_w=MEGA_BAR_CNT) + { + static float last_b=0; + alt_speed=(falt-last_b)*Freq/MEGA_BAR_CNT; + last_b=falt; + count=0; + } + else count++; + + Speed=MED2_Update(alt_speed*1000.0f, BAR_Med2)/1000.0f; + + return falt; +}*/ +//------------------------------------------------------------------------------ + + + +static float MEGA_ACC=0.01f; + +static const long MEGA_Count=60; // 600ms at 100Hz +static float MEGA_Alt_Buff[MEGA_Count]; +static float MEGA_Spd_Buff[MEGA_Count]; +static long MEGA_Index=0; + +static float MegaFilterAcc(struct ORI_Data& Data) +{ + float acc; + + acc=fabsf(Data.Bar.Acc)*100.0f; + float filt = MEGA_ACC; + if(acc>1) filt/=acc; + + acc=fabsf(Data.Iner.Z)*100.0f; + if(acc>1) filt/=acc; + + const float g=9.80665f; + + static float i_speed=0; + i_speed+=Data.Iner.Z*g/Data.Freq; + + + MEGA_Alt_Buff[MEGA_Index++]=i_speed; + if(MEGA_Index>=MEGA_Count) MEGA_Index=0; + static float delay_speed; + delay_speed=(delay_speed+MEGA_Alt_Buff[MEGA_Index])/2.0f; + + float shift=Data.Bar.Speed-delay_speed; + + for(int a=0; a + +#include "uart.h" +#include "tick.h" + +#include "sbus.h" + +#pragma pack(push,1) +union SBUS_Struct +{ + unsigned char data[25]; + struct + { + unsigned start : 8; + unsigned ch1 : 11; + unsigned ch2 : 11; + unsigned ch3 : 11; + unsigned ch4 : 11; + unsigned ch5 : 11; + unsigned ch6 : 11; + unsigned ch7 : 11; + unsigned ch8 : 11; + unsigned ch9 : 11; + unsigned ch10 : 11; + unsigned ch11 : 11; + unsigned ch12 : 11; + unsigned ch13 : 11; + unsigned ch14 : 11; + unsigned ch15 : 11; + unsigned ch16 : 11; + unsigned flags : 8; + unsigned end : 8; + } bus; +}; +#pragma pack(pop) + +// IBUS: LEN(1)+CMD(1)+DATA(0..32)+CHSM(2) + +#define SBUS_START 0x0F + +#define SBUS_CH17 0x01 +#define SBUS_CH18 0x02 + +#define SBUS_FRAMELOST 0x04 +#define SBUS_FAILSAFE 0x08 + +#define SBUS_LENGTH 25 + +void SBUS_Init() +{ + UART1_Init(100'000); + USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_RXNEIE; + USART1->CR2 = USART_CR2_STOP_1 | USART_CR2_RXINV; + USART1->CR1 |= USART_CR1_PCE | USART_CR1_PS | USART_CR1_UE; +} + +static const unsigned long Size = SBUS_LENGTH; +static char Buffer[Size]; + +static char Length = 0; + +static unsigned long Time; + +static bool Parse(SBUS_Data& Data, char byte) +{ + unsigned long tick=TICK_GetCount(); + + unsigned long wait = tick - Time; + if (wait > 4) Length = 0; // Protocol synchronization lost !!! + + Time=tick; + + if (!Length && (byte != SBUS_START)) return false; + + Buffer[Length++] = byte; + + if(Lengthbus.end!=0) return false; + + Data.X=frame->bus.ch1; + Data.Y=frame->bus.ch2; + Data.Z=frame->bus.ch3; + Data.W=frame->bus.ch4; + + Data.SWA=frame->bus.ch5; + Data.SWB=frame->bus.ch6; + Data.SWC=frame->bus.ch7; + Data.SWD=frame->bus.ch8; + + Data.VRA=frame->bus.ch9; + Data.VRB=frame->bus.ch10; + + Data.OTHER[0]=frame->bus.ch11; + Data.OTHER[1]=frame->bus.ch12; + Data.OTHER[2]=frame->bus.ch13; + Data.OTHER[3]=frame->bus.ch14; + Data.OTHER[4]=frame->bus.ch15; + Data.OTHER[5]=frame->bus.ch16; + + Data.OTHER[6]=(bool)(frame->bus.flags & SBUS_CH17); + Data.OTHER[7]=(bool)(frame->bus.flags & SBUS_CH18); + + Data.FailSafe=frame->bus.flags & SBUS_FAILSAFE; + Data.FrameLost=frame->bus.flags & SBUS_FRAMELOST; + + return true; +} + +bool SBUS_Update(SBUS_Data& Data, bool& Off) +{ + char buf[Size]; + unsigned long size = UART1_Recv(buf, Size); + + bool done = false; + for (long a = 0; a < size; a++) done = Parse(Data, buf[a]); + Off=Data.FailSafe; + return done; +} \ No newline at end of file diff --git a/dev/sbus.h b/dev/sbus.h new file mode 100644 index 0000000..ebc4dd5 --- /dev/null +++ b/dev/sbus.h @@ -0,0 +1,25 @@ +#pragma once + +#define JOY_MIN 174 + +#define JOY_MID 996 +#define JOY_MID_PITCH 983 +#define JOY_MID_ROLL 996 +#define JOY_MID_YAW 996 +#define JOY_MAX 1811 + +#define JOY_VAL 1.567f + +struct SBUS_Data // Radiomaster +{ + short Z, W, X, Y; + short SWA, SWB, SWC, SWD; + short VRA, VRB; + short OTHER[8]; + + bool FrameLost; + bool FailSafe; +}; + +void SBUS_Init(); +bool SBUS_Update(SBUS_Data& Data, bool& Off); diff --git a/dev/tele.cpp b/dev/tele.cpp new file mode 100644 index 0000000..8e45461 --- /dev/null +++ b/dev/tele.cpp @@ -0,0 +1,193 @@ +#include + +#include "gpio.h" + +#include "uart.h" +#include "tick.h" + +#include "tele.h" + +enum class RecvModeEnum : unsigned char { Begin, Head, Titles, Data, Auto, SetPID, GetPID, Done }; + +struct RecvHead +{ + RecvHead(){}; + RecvHead(RecvModeEnum mode, unsigned char size, unsigned char crc) + { + Mode = mode; + DataSize = size; + DataCRC8 = crc; + CRC8 = (unsigned char)((unsigned char)Mode ^ DataSize ^ DataCRC8); + } + + RecvModeEnum Mode; + unsigned char DataSize; + unsigned char DataCRC8; + + unsigned char CRC8; + + bool Check() + { + return CRC8 == (unsigned char)((unsigned char)Mode ^ DataSize ^ DataCRC8); + } +}; + +unsigned char GetCRC8(const void* arr, int size) +{ + unsigned char crc = 0; + for (int a = 0; a < size; a++) crc ^= ((unsigned char*)arr)[a]; + return crc; +} + +static RecvHead Tele_Mode(RecvModeEnum::Begin,0,0); + +void TELE_Init() +{ + UART3_Init(57600); +} + +static unsigned long TELE_LastTime=0; +static unsigned long TELE_WaitTimer=0; + +static unsigned long TELE_Count=0; + +static bool DataAuto=true; + +void TELE_Update(const void* info, unsigned long size, unsigned long update) +{ + + switch(Tele_Mode.Mode) + { + case RecvModeEnum::Begin: + { + unsigned char begin; + int len=UART3_Recv(&begin, 1); + TELE_WaitTimer=TICK_GetCount(); + if(len && begin==0xAA) Tele_Mode.Mode=RecvModeEnum::Head; + break; + } + + case RecvModeEnum::Head: + { + int len=UART3_Recv(0, 0); + if(len100) Tele_Mode.Mode=RecvModeEnum::Begin; + + if(DataAuto && (TICK_GetCount()-TELE_LastTime>update)) + { + TELE_LastTime=TICK_GetCount(); + + unsigned char h=0xAA; + UART3_Send(&h, 1); + + RecvHead head(RecvModeEnum::Data, size, GetCRC8(info, size)); + UART3_Send(&head, sizeof(head)); + UART3_Send(info, size); + } +} \ No newline at end of file diff --git a/dev/tele.h b/dev/tele.h new file mode 100644 index 0000000..0fe8abd --- /dev/null +++ b/dev/tele.h @@ -0,0 +1,4 @@ +#pragma once + +void TELE_Init(); +void TELE_Update(const void* info, unsigned long size, unsigned long update); diff --git a/drv/gpio.cpp b/drv/gpio.cpp new file mode 100644 index 0000000..d90b657 --- /dev/null +++ b/drv/gpio.cpp @@ -0,0 +1,37 @@ +#include "stm32g4xx.h" + +#include "gpio.h" + +void GPIO_InitPin(unsigned long I_Pin) +{ + unsigned long port = (I_Pin & 0x000000F0UL) >> 4; + GPIO_TypeDef* gpio = (GPIO_TypeDef*)(((unsigned char*)GPIOA) + (port * 0x0400)); + unsigned long rcc = 1UL << port; + unsigned long pin = I_Pin & 0x0000000FUL; + unsigned long af = (I_Pin & 0x0F000000UL) >> 24; + unsigned long pupd = (I_Pin & 0x00F00000UL) >> 20; + unsigned long ospeed = (I_Pin & 0x000F0000UL) >> 16; + unsigned long mode = (I_Pin & 0x0000F000UL) >> 12; + unsigned long otype = (I_Pin & 0x00000100UL) >> 8; + unsigned long set = (I_Pin & 0x00000200UL) >> 9; + //--- + if (!(RCC->AHB2ENR & rcc)) RCC->AHB2ENR |= rcc; + //--- + gpio->AFR[pin >> 3] &= ~(0x0000000FUL << ((pin & 0x07) * 4)); + gpio->AFR[pin >> 3] |= af << ((pin & 0x07) * 4); + //--- + gpio->OSPEEDR &= ~(0x00000003UL << (pin * 2)); + gpio->OSPEEDR |= ospeed << (pin * 2); + //--- + gpio->OTYPER &= ~(0x00000001UL << pin); + gpio->OTYPER |= otype << pin; + //--- + gpio->PUPDR &= ~(0x00000003UL << (pin * 2)); + gpio->PUPDR |= pupd << (pin * 2); + //--- + gpio->BSRR = 1 << (set ? pin : pin+16); + //--- + gpio->MODER &= ~(0x00000003UL << (pin * 2)); + gpio->MODER |= mode << (pin * 2); +} +//------------------------------------------------------------------------------ diff --git a/drv/gpio.h b/drv/gpio.h new file mode 100644 index 0000000..90da667 --- /dev/null +++ b/drv/gpio.h @@ -0,0 +1,69 @@ +#pragma once + +#define GPIO_PIN_0 0x00000000UL +#define GPIO_PIN_1 0x00000001UL +#define GPIO_PIN_2 0x00000002UL +#define GPIO_PIN_3 0x00000003UL +#define GPIO_PIN_4 0x00000004UL +#define GPIO_PIN_5 0x00000005UL +#define GPIO_PIN_6 0x00000006UL +#define GPIO_PIN_7 0x00000007UL +#define GPIO_PIN_8 0x00000008UL +#define GPIO_PIN_9 0x00000009UL +#define GPIO_PIN_10 0x0000000AUL +#define GPIO_PIN_11 0x0000000BUL +#define GPIO_PIN_12 0x0000000CUL +#define GPIO_PIN_13 0x0000000DUL +#define GPIO_PIN_14 0x0000000EUL +#define GPIO_PIN_15 0x0000000FUL + +#define GPIO_PORT_A 0x00000000UL +#define GPIO_PORT_B 0x00000010UL +#define GPIO_PORT_C 0x00000020UL +#define GPIO_PORT_D 0x00000030UL +#define GPIO_PORT_E 0x00000040UL +#define GPIO_PORT_F 0x00000070UL +#define GPIO_PORT_G 0x00000080UL +#define GPIO_PORT_H 0x00000090UL +#define GPIO_PORT_I 0x000000A0UL +#define GPIO_PORT_J 0x000000B0UL +#define GPIO_PORT_K 0x000000C0UL + +#define GPIO_PUSHPULL 0x00000000UL +#define GPIO_OPENDRAIN 0x00000100UL + +#define GPIO_RESET 0x00000000UL +#define GPIO_SET 0x00000200UL + +#define GPIO_INPUT 0x00000000UL +#define GPIO_OUTPUT 0x00001000UL +#define GPIO_ALTER 0x00002000UL +#define GPIO_ANALOG 0x00003000UL + +#define GPIO_OSPEED_LOW 0x00000000UL +#define GPIO_OSPEED_MEDIUM 0x00010000UL +#define GPIO_OSPEED_FAST 0x00020000UL +#define GPIO_OSPEED_HIGH 0x00030000UL + +#define GPIO_NOPUPD 0x00000000UL +#define GPIO_PULLUP 0x00100000UL +#define GPIO_PULLDOWN 0x00200000UL + +#define GPIO_AF0 0x00000000UL +#define GPIO_AF1 0x01000000UL +#define GPIO_AF2 0x02000000UL +#define GPIO_AF3 0x03000000UL +#define GPIO_AF4 0x04000000UL +#define GPIO_AF5 0x05000000UL +#define GPIO_AF6 0x06000000UL +#define GPIO_AF7 0x07000000UL +#define GPIO_AF8 0x08000000UL +#define GPIO_AF9 0x09000000UL +#define GPIO_AF10 0x0A000000UL +#define GPIO_AF11 0x0B000000UL +#define GPIO_AF12 0x0C000000UL +#define GPIO_AF13 0x0D000000UL +#define GPIO_AF14 0x0E000000UL +#define GPIO_AF15 0x0F000000UL + +void GPIO_InitPin(unsigned long I_Pin); diff --git a/drv/i2c.cpp b/drv/i2c.cpp new file mode 100644 index 0000000..816fcc6 --- /dev/null +++ b/drv/i2c.cpp @@ -0,0 +1,201 @@ +#include "stm32g4xx.h" + +#include + +#include "gpio.h" + +#include "i2c.h" + +static void Init(I2C_TypeDef* I2C) +{ + I2C->TIMINGR = 0x00303D5BUL; // 100kHz + + //I2C->TIMINGR = 0x30108DFF; + + I2C->CR1 = I2C_CR1_PE; + + while(I2C->ISR & I2C_ISR_BUSY) { } +} +//------------------------------------------------------------------------------ + +void I2C2_Init() +{ + if (RCC->APB1ENR1 & RCC_APB1ENR1_I2C2EN) return; + + RCC->APB1ENR1 |= RCC_APB1ENR1_I2C2EN; + + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOAEN; + + GPIO_InitPin(GPIO_PIN_8 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF4 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); + GPIO_InitPin(GPIO_PIN_9 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF4 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); + + Init(I2C2); +} +//------------------------------------------------------------------------------ + +void I2C1_Init() +{ + if (RCC->APB1ENR1 & RCC_APB1ENR1_I2C1EN) return; + + RCC->APB1ENR1 |= RCC_APB1ENR1_I2C1EN; + + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOBEN; + + GPIO_InitPin(GPIO_PIN_8 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF4 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); + GPIO_InitPin(GPIO_PIN_9 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF4 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); + + Init(I2C1); +} +//------------------------------------------------------------------------------ + +static void Stop(I2C_TypeDef* I2C) +{ + I2C->CR2 |= I2C_CR2_STOP; + while (!(I2C->ISR & I2C_ISR_STOPF)) { asm volatile("NOP"); } + I2C->ICR = I2C_ICR_STOPCF; +} +//------------------------------------------------------------------------------ + +static void Read(I2C_TypeDef* I2C, unsigned char Address, unsigned char* Data, unsigned char Size) +{ + I2C->CR2 &= ~(I2C_CR2_SADD_Msk | I2C_CR2_NBYTES_Msk); + I2C->CR2 |= (Address << (I2C_CR2_SADD_Pos + 1)) | I2C_CR2_RD_WRN | (((unsigned long)Size)<CR2 |= I2C_CR2_START; + + while (Size--) + { + while (!(I2C->ISR & I2C_ISR_RXNE)) { } + *Data++ = I2C->RXDR; + } + + + + +} +//------------------------------------------------------------------------------ + +static void Write(I2C_TypeDef* I2C, unsigned char Address, const unsigned char* Data, unsigned char Size) +{ + I2C->CR2 &= ~(I2C_CR2_SADD_Msk | I2C_CR2_RD_WRN | I2C_CR2_NBYTES_Msk); + I2C->CR2 |= (Address << (I2C_CR2_SADD_Pos + 1)) | (((unsigned long)Size)<CR2 |= I2C_CR2_START; + + while(I2C->CR2 & I2C_CR2_START) { asm volatile("NOP"); } + + while (Size--) + { + while (!(I2C->ISR & I2C_ISR_TXE)) { asm volatile("NOP"); } + I2C->TXDR = *Data++; + } + + while(!(I2C->ISR & I2C_ISR_TC)) { asm volatile("NOP"); }//??? + + + + + +} +//------------------------------------------------------------------------------ + +static void Write2(I2C_TypeDef* I2C, unsigned char Address, const unsigned char* Data1, unsigned char Size1, const unsigned char* Data2, unsigned char Size2) +{ + I2C->CR2 &= ~(I2C_CR2_SADD_Msk | I2C_CR2_RD_WRN | I2C_CR2_NBYTES_Msk); + I2C->CR2 |= (Address << (I2C_CR2_SADD_Pos + 1)) | (((unsigned long)Size1+Size2)<CR2 |= I2C_CR2_START; + + while (Size1--) + { + while (!(I2C->ISR & I2C_ISR_TXE)) { asm volatile("NOP"); } + I2C->TXDR = *Data1++; + } + + while (Size2--) + { + while (!(I2C->ISR & I2C_ISR_TXE)) { asm volatile("NOP"); } + I2C->TXDR = *Data2++; + } + + while(!(I2C->ISR & I2C_ISR_TC)) { asm volatile("NOP"); } + + +} +//------------------------------------------------------------------------------ + +void I2C2_Write(unsigned char Address, unsigned char Data) +{ + Write(I2C2, Address, &Data, 1); +} +//------------------------------------------------------------------------------ + +void I2C2_Write(unsigned char Address, const void* Data, unsigned char Size) +{ + Write(I2C2, Address, (unsigned char*)Data, Size); +} +//------------------------------------------------------------------------------ + +void I2C2_Read(unsigned char Address, void* Data, unsigned char Size) +{ + Read(I2C2, Address, (unsigned char*)Data, Size); +} +//------------------------------------------------------------------------------ + +void I2C2_Stop() +{ + Stop(I2C2); +} +//------------------------------------------------------------------------------ + + + +void I2C1_Write(unsigned char Address, unsigned char Data) +{ + Write(I2C1, Address, &Data, 1); +} +//------------------------------------------------------------------------------ + +void I2C1_Write(unsigned char Address, const void* Data, unsigned char Size) +{ + Write(I2C1, Address, (unsigned char*)Data, Size); +} +//------------------------------------------------------------------------------ + +void I2C1_Write2(unsigned char Address, const void* Data1, unsigned char Size1, const void* Data2, unsigned char Size2) +{ + Write2(I2C1, Address, (unsigned char*)Data1, Size1, (unsigned char*)Data2, Size2); +} +//------------------------------------------------------------------------------ + +void I2C1_Read(unsigned char Address, void* Data, unsigned char Size) +{ + Read(I2C1, Address, (unsigned char*)Data, Size); +} +//------------------------------------------------------------------------------ + +void I2C1_Stop() +{ + Stop(I2C1); +} +//------------------------------------------------------------------------------ + + + +extern "C" { + +int8_t I2C1_WriteBytes(uint8_t addr, const uint8_t *data, uint8_t size) +{ + Write(I2C1, addr, (unsigned char*)data, size); + + return 0; +} + +int8_t I2C1_ReadBytes(uint8_t addr, uint8_t *data, uint8_t size) +{ + Read(I2C1, addr,(unsigned char*)data, size); + + return 0; +} + +} // extern "C" + + + diff --git a/drv/i2c.h b/drv/i2c.h new file mode 100644 index 0000000..498e153 --- /dev/null +++ b/drv/i2c.h @@ -0,0 +1,27 @@ +#pragma once + +struct I2C_Device +{ + unsigned char* Buffer; + unsigned char Size; + void (*CallbackProc)(unsigned char Address, const unsigned char* Data, unsigned char Size); + + unsigned char Address; + unsigned char Write; + unsigned char Read; + + I2C_Device* Next; +}; + +void I2C2_Init(); +void I2C2_Write(unsigned char Address, unsigned char Data); +void I2C2_Write(unsigned char Address, const void* Data, unsigned char Size); +void I2C2_Read(unsigned char Address, void* Data, unsigned char Size); +void I2C2_Stop(); + +void I2C1_Init(); +void I2C1_Write(unsigned char Address, unsigned char Data); +void I2C1_Write(unsigned char Address, const void* Data, unsigned char Size); +void I2C1_Write2(unsigned char Address, const void* Data1, unsigned char Size1, const void* Data2, unsigned char Size2); +void I2C1_Read(unsigned char Address, void* Data, unsigned char Size); +void I2C1_Stop(); diff --git a/drv/iwdg.cpp b/drv/iwdg.cpp new file mode 100644 index 0000000..44c5f43 --- /dev/null +++ b/drv/iwdg.cpp @@ -0,0 +1,18 @@ +#include "stm32g4xx.h" + +#include "iwdg.h" + +void InitIWDG(unsigned short Reload) +{ + IWDG->KR=0x0000CCCC; + IWDG->KR=0x00005555; + IWDG->PR=0; + IWDG->RLR=Reload; + while(IWDG->SR) { asm volatile("NOP"); } + IWDG->KR=0x0000AAAA; +} + +void PingIWDG() +{ + IWDG->KR=0x0000AAAA; +} diff --git a/drv/iwdg.h b/drv/iwdg.h new file mode 100644 index 0000000..ab28176 --- /dev/null +++ b/drv/iwdg.h @@ -0,0 +1,4 @@ +#pragma once + +void InitIWDG(unsigned short Reload); +void PingIWDG(); diff --git a/drv/pwm.cpp b/drv/pwm.cpp new file mode 100644 index 0000000..f1b3a3c --- /dev/null +++ b/drv/pwm.cpp @@ -0,0 +1,85 @@ +#include "stm32g4xx.h" + +#include "gpio.h" + +#include "pwm.h" + +bool PWM_Enable=false; +short PWM_work_min = 1050;//??? + +inline static unsigned short Mid(unsigned short Val, unsigned short Min, unsigned short Max) +{ + if(ValMax) return Max; + return Val; +} + + +void PWM_Init(unsigned long Freq) +{ + GPIO_InitPin(GPIO_PIN_0 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF1); + GPIO_InitPin(GPIO_PIN_1 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF1); + GPIO_InitPin(GPIO_PIN_2 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF1); + GPIO_InitPin(GPIO_PIN_3 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF1); + + RCC->APB1ENR1 |= RCC_APB1ENR1_TIM2EN; + TIM2->CR2 = 0; + + + + TIM2->ARR = 1000 - 1; //The comparison range is 100 + TIM2->PSC = (16'000'000/1000/16000)-1; // The divider is set to 16000Hz + + TIM2->CCMR1 = TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1PE; //PWM mode 1 for CH1 + TIM2->CCMR1|= TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2PE; // PWM mode 1 for CH2 + TIM2->CCMR2 = TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3PE; // PWM mode 1 for CH3 + TIM2->CCMR2|= TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4PE; // PWM mode 1 for CH4 + + TIM2->CCER = TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E |TIM_CCER_CC4E; // CH1 and CH2 outputs are active + TIM2->BDTR = TIM_BDTR_MOE; // Allow active outputs to work + TIM2->CR1 = TIM_CR1_CEN; // Timer is running + for(int a=0; a<100000; a++) { asm volatile("NOP");} + +} +//------------------------------------------------------------------------------ + +static void Stop() +{ + PWM_Enable=false; + + TIM2->CCER=0; + +} +//------------------------------------------------------------------------------ + +void PWM_SetQuad(short Pow[4], unsigned short Min, unsigned short Max) +{ + if(!Pow) { Stop(); return; } + TIM2->CCR1 = Mid(Pow[0], Min, Max); //M1 + TIM2->CCR2 = Mid(Pow[1], Min, Max); //M2 + TIM2->CCR3 = Mid(Pow[2], Min, Max); //M3 + TIM2->CCR4 = Mid(Pow[3], Min, Max); //M4 + + + + bool en=false; + for(int a=0; a<4; a++) if(Pow[a]>PWM_work_min) en=true; + PWM_Enable=en; +} +//------------------------------------------------------------------------------ + + + +void PWM_SetAll(unsigned short Pow) +{ + + TIM2->CCR1 = Pow; + TIM2->CCR2 = Pow; + TIM2->CCR3 = Pow; + TIM2->CCR4 = Pow; + + bool en=false; + if(Pow>PWM_work_min) en=true; + PWM_Enable=en; +} +//------------------------------------------------------------------------------ diff --git a/drv/pwm.h b/drv/pwm.h new file mode 100644 index 0000000..2d6f17c --- /dev/null +++ b/drv/pwm.h @@ -0,0 +1,7 @@ +#pragma once + +extern bool PWM_Enable; + +void PWM_Init(unsigned long Freq); +void PWM_SetQuad(short M[4], unsigned short Min, unsigned short Max); +void PWM_SetAll(unsigned short Pow); diff --git a/drv/spi.cpp b/drv/spi.cpp new file mode 100644 index 0000000..4ef4fc1 --- /dev/null +++ b/drv/spi.cpp @@ -0,0 +1,138 @@ +#include "stm32g4xx.h" + +#include "gpio.h" + +#include "spi.h" + +static void Init(SPI_TypeDef* SPI) +{ + SPI->CR1 = SPI_CR1_CPHA | SPI_CR1_CPOL | SPI_CR1_SSI | SPI_CR1_SSM | (SPI_CR1_BR_0 | SPI_CR1_BR_1) | SPI_CR1_MSTR; + SPI->CR2 = SPI_CR2_DS_0 | SPI_CR2_DS_1 | SPI_CR2_DS_2 | SPI_CR2_FRXTH; + SPI->CR1 |= SPI_CR1_SPE; +} +//------------------------------------------------------------------------------ + +void SPI1_Init() +{ + if(RCC->APB2ENR & RCC_APB2ENR_SPI1EN) return; + + RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; + + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOAEN; + GPIO_InitPin(GPIO_PIN_5 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH); // SCK + GPIO_InitPin(GPIO_PIN_6 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH); // MISO + + GPIO_InitPin(GPIO_PIN_7 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH); // MOSI + + + + GPIO_InitPin(GPIO_PIN_4 | GPIO_PORT_A | GPIO_OUTPUT | GPIO_OSPEED_HIGH | GPIO_SET); // NCS -> PMW3901 + + + + + Init(SPI1); +} +//------------------------------------------------------------------------------ + +static void Trans(SPI_TypeDef* SPI, const void* WriteData, void* ReadData, unsigned long Size) +{ + unsigned char* dr=(unsigned char*)ReadData; + unsigned char* dw=(unsigned char*)WriteData; + + volatile char& DR = *((volatile char*)&(SPI->DR)); + + while (Size--) + { + while (!(SPI->SR & SPI_SR_TXE)) { asm volatile("NOP"); } + if (dw) DR = *(dw++); + else DR = 0x00; + + while (!(SPI->SR & SPI_SR_RXNE)) { asm volatile("NOP"); } + if (dr) *(dr++) = DR; + else volatile char t = DR; + } + + while (SPI->SR & SPI_SR_BSY) { asm volatile("NOP"); } +} +//------------------------------------------------------------------------------ + +static inline void CS_IMU(bool En) +{ + if(En) GPIOB->BSRR = GPIO_BSRR_BR_12; + else GPIOB->BSRR = GPIO_BSRR_BS_12; + + for (unsigned long a = 0; a < 21; a++) { asm volatile("NOP"); } +} +//------------------------------------------------------------------------------ + +void SPI1_TransferCons(const void* WriteData, unsigned long WriteSize, void* ReadData, unsigned long ReadSize) +{ + CS_IMU(true); + + Trans(SPI1, WriteData, 0, WriteSize); + Trans(SPI1, 0, ReadData, ReadSize); + + CS_IMU(false); +} +//------------------------------------------------------------------------------ + +void SPI1_TransferParallel(const void* WriteData, void* ReadData, unsigned long Size) +{ + CS_IMU(true); + + Trans(SPI1, WriteData, ReadData, Size); + + CS_IMU(false); +} +//------------------------------------------------------------------------------ + +//------------------------------------------------------------------------------ + +void SPI2_Init() +{ + + if ( RCC->APB1ENR1&RCC_APB1ENR1_SPI2EN) return; + + RCC->APB1ENR1 |= RCC_APB1ENR1_SPI2EN; + + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOAEN; + RCC->AHB2ENR |= RCC_AHB2ENR_GPIOBEN; + + GPIO_InitPin(GPIO_PIN_10 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); // MISO + GPIO_InitPin(GPIO_PIN_11 | GPIO_PORT_A | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH | GPIO_OPENDRAIN | GPIO_PULLUP); // MOSI + + + GPIO_InitPin(GPIO_PIN_13 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF5 | GPIO_OSPEED_HIGH| GPIO_OPENDRAIN | GPIO_PULLUP); // SCK + GPIO_InitPin(GPIO_PIN_12 | GPIO_PORT_B | GPIO_OUTPUT | GPIO_OSPEED_HIGH | GPIO_SET| GPIO_OPENDRAIN | GPIO_PULLUP); // NSS -> PMW3901 + + + + + + Init(SPI2); +} +//------------------------------------------------------------------------------ + +//------------------------------------------------------------------------------ + +void SPI2_TransferCons(const void* WriteData, unsigned long WriteSize, void* ReadData, unsigned long ReadSize) +{ + CS_IMU(true); + + Trans(SPI2, WriteData, 0, WriteSize); + Trans(SPI2, 0, ReadData, ReadSize); + + CS_IMU(false); +} +//------------------------------------------------------------------------------ + +void SPI2_TransferParallel(const void* WriteData, void* ReadData, unsigned long Size) +{ + CS_IMU(true); + + Trans(SPI2, WriteData, ReadData, Size); + + CS_IMU(false); +} +//----------------------------------------------------------------------------- diff --git a/drv/spi.h b/drv/spi.h new file mode 100644 index 0000000..845bb65 --- /dev/null +++ b/drv/spi.h @@ -0,0 +1,12 @@ +#pragma once + +void SPI1_Init(); + +void SPI1_TransferCons(const void* WriteData, unsigned long WriteSize, void* ReadData, unsigned long ReadSize); +void SPI1_TransferParallel(const void* WriteData, void* ReadData, unsigned long Size); + + +void SPI2_Init(); + +void SPI2_TransferCons(const void* WriteData, unsigned long WriteSize, void* ReadData, unsigned long ReadSize); +void SPI2_TransferParallel(const void* WriteData, void* ReadData, unsigned long Size); diff --git a/drv/tick.cpp b/drv/tick.cpp new file mode 100644 index 0000000..3ed066a --- /dev/null +++ b/drv/tick.cpp @@ -0,0 +1,36 @@ +#include "stm32g4xx.h" + +#include "tick.h" + +static unsigned long Tick = 0; + +extern "C" void SysTick_Handler() +{ + Tick++; +} +//------------------------------------------------------------------------------ + +void TICK_Init() +{ + SysTick->LOAD = SystemCoreClock / 1000; + SysTick->VAL = 0UL; + SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_ENABLE_Msk; + + NVIC_SetPriority(SysTick_IRQn, 0); +} +//------------------------------------------------------------------------------ + +unsigned long TICK_GetCount() // ms +{ + return Tick; +} +//------------------------------------------------------------------------------ + + +void Tick_Delay(unsigned long ms) +{ + const unsigned long start = Tick; + while ((Tick - start) < ms) { + __NOP(); + } +} \ No newline at end of file diff --git a/drv/tick.h b/drv/tick.h new file mode 100644 index 0000000..ded0461 --- /dev/null +++ b/drv/tick.h @@ -0,0 +1,5 @@ +#pragma once + +void TICK_Init(); +unsigned long TICK_GetCount(); +void Tick_Delay(unsigned long ms); \ No newline at end of file diff --git a/drv/tim.cpp b/drv/tim.cpp new file mode 100644 index 0000000..57a2fe2 --- /dev/null +++ b/drv/tim.cpp @@ -0,0 +1,34 @@ +#include "stm32g4xx.h" + +#include "tim.h" + +static void (*TIM7_Proc)() = 0; + +extern "C" void TIM7_IRQHandler() +{ + TIM7->SR = 0; + TIM7_Proc(); +} +//------------------------------------------------------------------------------ + +void TIM7_Init(long Priority) +{ + RCC->APB1ENR1 |= RCC_APB1ENR1_TIM7EN; + + TIM7->CR1 = 0; + TIM7->ARR = 1000 - 1; + TIM7->DIER = TIM_DIER_UIE; + + NVIC_SetPriority(TIM7_IRQn, Priority); + NVIC_EnableIRQ(TIM7_IRQn); +} +//------------------------------------------------------------------------------ + +void TIM7_Update(unsigned long Freq, void (*Proc)()) +{ + TIM7->CR1 = 0; + TIM7->PSC = (SystemCoreClock / 1000 / Freq) - 1; + TIM7_Proc = Proc; + TIM7->CR1 = TIM_CR1_CEN; +} +//------------------------------------------------------------------------------ \ No newline at end of file diff --git a/drv/tim.h b/drv/tim.h new file mode 100644 index 0000000..623fc31 --- /dev/null +++ b/drv/tim.h @@ -0,0 +1,4 @@ +#pragma once + +void TIM7_Init(long Priority); +void TIM7_Update(unsigned long Freq, void (*UpdateProc)()); diff --git a/drv/uart.cpp b/drv/uart.cpp new file mode 100644 index 0000000..0b91f5a --- /dev/null +++ b/drv/uart.cpp @@ -0,0 +1,237 @@ +#include "stm32g4xx.h" + +#include + +#include "gpio.h" + +#include "uart.h" + +static const unsigned long UART_BuferSize=256; + +struct UART_Data +{ + USART_TypeDef* UART; + + struct + { + unsigned long Size; + unsigned char* Buffer; + unsigned short Head; + unsigned short Tail; + unsigned short Push; + unsigned short Pull; + } Recv, Send; +}; + +static unsigned char UART3_BufferRecv[UART_BuferSize], UART3_BufferSend[UART_BuferSize]; +static UART_Data UART3_Data{ USART3, {sizeof(UART3_BufferRecv), UART3_BufferRecv, 0, 0, 0, 0}, {sizeof(UART3_BufferSend), UART3_BufferSend, 0, 0, 0, 0} }; + +static unsigned char UART2_BufferRecv[UART_BuferSize], UART2_BufferSend[UART_BuferSize]; +static UART_Data UART2_Data{ USART2, {sizeof(UART2_BufferRecv), UART2_BufferRecv, 0, 0, 0, 0}, {sizeof(UART2_BufferSend), UART2_BufferSend, 0, 0, 0, 0} }; + +static unsigned char UART1_BufferRecv[UART_BuferSize], UART1_BufferSend[UART_BuferSize]; +static UART_Data UART1_Data{ USART1, {sizeof(UART1_BufferRecv), UART1_BufferRecv, 0, 0, 0, 0}, {sizeof(UART1_BufferSend), UART1_BufferSend, 0, 0, 0, 0} }; + +static void IRQHandler(UART_Data& Uart) +{ + unsigned long isr = Uart.UART->ISR; + if(isr & USART_ISR_RXNE) + { + Uart.Recv.Buffer[Uart.Recv.Head] = Uart.UART->RDR; + if(Uart.Recv.Push-Uart.Recv.Pull=Uart.Recv.Size) Uart.Recv.Head=0; + } + if(isr & USART_ISR_TXE) + { + if(Uart.Send.Push != Uart.Send.Pull) + { + Uart.UART->TDR = Uart.Send.Buffer[Uart.Send.Tail++]; + if(Uart.Send.Tail>=Uart.Send.Size) Uart.Send.Tail=0; + Uart.Send.Pull++; + } + else Uart.UART->CR1 &= ~USART_CR1_TXEIE; + } +} +//------------------------------------------------------------------------------ + +extern "C" void USART3_IRQHandler() +{ + IRQHandler(UART3_Data); +} +//------------------------------------------------------------------------------ + +extern "C" void USART2_IRQHandler() +{ + IRQHandler(UART2_Data); +} +//------------------------------------------------------------------------------ + +extern "C" void USART1_IRQHandler() +{ + IRQHandler(UART1_Data); +} +//------------------------------------------------------------------------------ + +static void Init(USART_TypeDef* USART, unsigned long Baud) +{ + USART->CR1 = 0; + + USART->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_RXNEIE; + + //USART->BRR = SystemCoreClock / 4 / Baud; + USART->BRR = SystemCoreClock / Baud; + + USART->CR3 |= USART_CR3_OVRDIS; + USART->CR1 |= USART_CR1_UE; +} +//------------------------------------------------------------------------------ + +void UART3_Init(unsigned long Baud) +{ + if (RCC->APB1ENR1 & RCC_APB1ENR1_USART3EN) return; + + RCC->APB1ENR1 |= RCC_APB1ENR1_USART3EN; + + GPIO_InitPin(GPIO_PIN_10 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + GPIO_InitPin(GPIO_PIN_11 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + + Init(USART3, Baud); + + NVIC_SetPriority(USART3_IRQn, 0); + NVIC_EnableIRQ(USART3_IRQn); +} +//------------------------------------------------------------------------------ + +void UART2_Init(unsigned long Baud) +{ + if (RCC->APB1ENR1 & RCC_APB1ENR1_USART2EN) return; + + RCC->APB1ENR1 |= RCC_APB1ENR1_USART2EN; + + GPIO_InitPin(GPIO_PIN_3 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + GPIO_InitPin(GPIO_PIN_4 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + + Init(USART2, Baud); + + NVIC_SetPriority(USART2_IRQn, 0); + NVIC_EnableIRQ(USART2_IRQn); +} +//------------------------------------------------------------------------------ + +void UART1_Init(unsigned long Baud) +{ + if (RCC->APB2ENR & RCC_APB2ENR_USART1EN) return; + + RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + + GPIO_InitPin(GPIO_PIN_6 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + GPIO_InitPin(GPIO_PIN_7 | GPIO_PORT_B | GPIO_ALTER | GPIO_AF7 | GPIO_OSPEED_HIGH); + + Init(USART1, Baud); + + NVIC_SetPriority(USART1_IRQn, 0); + NVIC_EnableIRQ(USART1_IRQn); +} +//------------------------------------------------------------------------------ + +static unsigned long Recv(UART_Data& Uart, void* Data, unsigned long Size) +{ + if(!Data) return Uart.Recv.Push-Uart.Recv.Pull; + + unsigned char* data=(unsigned char*)Data; + unsigned long size = 0; + + while (size < Size) + { + if (Uart.Recv.Push == Uart.Recv.Pull) break; + data[size++] = Uart.Recv.Buffer[Uart.Recv.Tail++]; + if(Uart.Recv.Tail>=Uart.Recv.Size) Uart.Recv.Tail=0; + Uart.Recv.Pull++; + } + return size; +} +//------------------------------------------------------------------------------ + +static unsigned long Send(UART_Data& Uart, const void* Data, unsigned long Size) +{ + unsigned char* data=(unsigned char*)Data; + unsigned long size = 0; + + while (size < Size) + { + if (Uart.Send.Push - Uart.Send.Pull >= Uart.Send.Size) break; + Uart.Send.Buffer[Uart.Send.Head++] = data[size++]; + if(Uart.Send.Head>=Uart.Send.Size) Uart.Send.Head=0; + Uart.Send.Push++; + } + + Uart.UART->CR1 |= USART_CR1_TXEIE; + + return size; +} +//------------------------------------------------------------------------------ + +static inline void Flush(UART_Data& Uart) +{ + Uart.Recv.Tail=Uart.Recv.Head; + Uart.Recv.Pull=Uart.Recv.Push; +} +//------------------------------------------------------------------------------ + +unsigned long UART3_Recv(void* Data, unsigned long Size) +{ + return Recv(UART3_Data, Data, Size); +} +//------------------------------------------------------------------------------ + +void UART3_Flush() +{ + Flush(UART3_Data); +} +//------------------------------------------------------------------------------ + +unsigned long UART3_Send(const void* Data, unsigned long Size) +{ + return Send(UART3_Data, Data, Size); +} +//------------------------------------------------------------------------------ + +unsigned long UART2_Recv(void* Data, unsigned long Size) +{ + return Recv(UART2_Data, Data, Size); +} +//------------------------------------------------------------------------------ + +void UART2_Flush() +{ + Flush(UART2_Data); +} +//------------------------------------------------------------------------------ + +unsigned long UART2_Send(const void* Data, unsigned long Size) +{ + return Send(UART2_Data, Data, Size); +} +//------------------------------------------------------------------------------ + +unsigned long UART1_Recv(void* Data, unsigned long Size) +{ + return Recv(UART1_Data, Data, Size); +} +//------------------------------------------------------------------------------ + +void UART1_Flush() +{ + Flush(UART1_Data); +} +//------------------------------------------------------------------------------ + +unsigned long UART1_Send(const void* Data, unsigned long Size) +{ + return Send(UART1_Data, Data, Size); +} +//------------------------------------------------------------------------------ diff --git a/drv/uart.h b/drv/uart.h new file mode 100644 index 0000000..7082c0e --- /dev/null +++ b/drv/uart.h @@ -0,0 +1,16 @@ +#pragma once + +void UART3_Init(unsigned long Baud); +void UART3_Flush(); +unsigned long UART3_Recv(void* Data, unsigned long Size); +unsigned long UART3_Send(const void* Data, unsigned long Size); + +void UART2_Init(unsigned long Baud); +void UART2_Flush(); +unsigned long UART2_Recv(void* Data, unsigned long Size); +unsigned long UART2_Send(const void* Data, unsigned long Size); + +void UART1_Init(unsigned long Baud); +void UART1_Flush(); +unsigned long UART1_Recv(void* Data, unsigned long Size); +unsigned long UART1_Send(const void* Data, unsigned long Size); diff --git a/drv/vl53l0x.cpp b/drv/vl53l0x.cpp new file mode 100644 index 0000000..2e077d8 --- /dev/null +++ b/drv/vl53l0x.cpp @@ -0,0 +1,1053 @@ +// Most of the functionality of this library is based on the VL53L0X API +// provided by ST (STSW-IMG005), and some of the explanatory comments are quoted +// or paraphrased from the API source code, API user manual (UM2039), and the +// VL53L0X datasheet. + +#include "VL53L0X.h" +#include "i2c.h" + +// Defines ///////////////////////////////////////////////////////////////////// + +// The Arduino two-wire interface uses a 7-bit number for the address, +// and sets the last bit correctly based on reads and writes +#define ADDRESS_DEFAULT 0b0101001 + +// Record the current time to check an upcoming timeout against +#define startTimeout() (timeout_start_ms = TICK_GetCount()) + +// Check if timeout is enabled (set to nonzero value) and has expired +#define checkTimeoutExpired() (io_timeout > 0 && ((uint16_t)(TICK_GetCount() - timeout_start_ms) > io_timeout)) + +// Decode VCSEL (vertical cavity surface emitting laser) pulse period in PCLKs +// from register value +// based on VL53L0X_decode_vcsel_period() +#define decodeVcselPeriod(reg_val) (((reg_val) + 1) << 1) + +// Encode VCSEL pulse period register value from period in PCLKs +// based on VL53L0X_encode_vcsel_period() +#define encodeVcselPeriod(period_pclks) (((period_pclks) >> 1) - 1) + +// Calculate macro period in *nanoseconds* from VCSEL period in PCLKs +// based on VL53L0X_calc_macro_period_ps() +// PLL_period_ps = 1655; macro_period_vclks = 2304 +#define calcMacroPeriod(vcsel_period_pclks) ((((uint32_t)2304 * (vcsel_period_pclks) * 1655) + 500) / 1000) + +// Constructors //////////////////////////////////////////////////////////////// + +VL53L0X::VL53L0X() + : address(ADDRESS_DEFAULT) + , io_timeout(0) // no timeout + , did_timeout(false) +{ +} + +// Public Methods ////////////////////////////////////////////////////////////// + +void VL53L0X::setAddress(uint8_t new_addr) +{ + writeReg(I2C_SLAVE_DEVICE_ADDRESS, new_addr & 0x7F); + address = new_addr; +} + +// Initialize sensor using sequence based on VL53L0X_DataInit(), +// VL53L0X_StaticInit(), and VL53L0X_PerformRefCalibration(). +// This function does not perform reference SPAD calibration +// (VL53L0X_PerformRefSpadManagement()), since the API user manual says that it +// is performed by ST on the bare modules; it seems like that should work well +// enough unless a cover glass is added. +// If io_2v8 (optional) is true or not given, the sensor is configured for 2V8 +// mode. +bool VL53L0X::init(bool io_2v8) +{ + // check model ID register (value specified in datasheet) + if (readReg(IDENTIFICATION_MODEL_ID) != 0xEE) { return false; } + + // VL53L0X_DataInit() begin + + // sensor uses 1V8 mode for I/O by default; switch to 2V8 mode if necessary + if (io_2v8) + { + writeReg(VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV, + readReg(VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV) | 0x01); // set bit 0 + } + + // "Set I2C standard mode" + writeReg(0x88, 0x00); + + writeReg(0x80, 0x01); + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + stop_variable = readReg(0x91); + writeReg(0x00, 0x01); + writeReg(0xFF, 0x00); + writeReg(0x80, 0x00); + + // disable SIGNAL_RATE_MSRC (bit 1) and SIGNAL_RATE_PRE_RANGE (bit 4) limit checks + writeReg(MSRC_CONFIG_CONTROL, readReg(MSRC_CONFIG_CONTROL) | 0x12); + + // set final range signal rate limit to 0.25 MCPS (million counts per second) + setSignalRateLimit(0.25); + + writeReg(SYSTEM_SEQUENCE_CONFIG, 0xFF); + + // VL53L0X_DataInit() end + + // VL53L0X_StaticInit() begin + + uint8_t spad_count; + bool spad_type_is_aperture; + if (!getSpadInfo(&spad_count, &spad_type_is_aperture)) { return false; } + + // The SPAD map (RefGoodSpadMap) is read by VL53L0X_get_info_from_device() in + // the API, but the same data seems to be more easily readable from + // GLOBAL_CONFIG_SPAD_ENABLES_REF_0 through _6, so read it from there + uint8_t ref_spad_map[6]; + readMulti(GLOBAL_CONFIG_SPAD_ENABLES_REF_0, ref_spad_map, 6); + + // -- VL53L0X_set_reference_spads() begin (assume NVM values are valid) + + writeReg(0xFF, 0x01); + writeReg(DYNAMIC_SPAD_REF_EN_START_OFFSET, 0x00); + writeReg(DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD, 0x2C); + writeReg(0xFF, 0x00); + writeReg(GLOBAL_CONFIG_REF_EN_START_SELECT, 0xB4); + + uint8_t first_spad_to_enable = spad_type_is_aperture ? 12 : 0; // 12 is the first aperture spad + uint8_t spads_enabled = 0; + + for (uint8_t i = 0; i < 48; i++) + { + if (i < first_spad_to_enable || spads_enabled == spad_count) + { + // This bit is lower than the first one that should be enabled, or + // (reference_spad_count) bits have already been enabled, so zero this bit + ref_spad_map[i / 8] &= ~(1 << (i % 8)); + } + else if ((ref_spad_map[i / 8] >> (i % 8)) & 0x1) + { + spads_enabled++; + } + } + + writeMulti(GLOBAL_CONFIG_SPAD_ENABLES_REF_0, ref_spad_map, 6); + + // -- VL53L0X_set_reference_spads() end + + // -- VL53L0X_load_tuning_settings() begin + // DefaultTuningSettings from vl53l0x_tuning.h + + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + + writeReg(0xFF, 0x00); + writeReg(0x09, 0x00); + writeReg(0x10, 0x00); + writeReg(0x11, 0x00); + + writeReg(0x24, 0x01); + writeReg(0x25, 0xFF); + writeReg(0x75, 0x00); + + writeReg(0xFF, 0x01); + writeReg(0x4E, 0x2C); + writeReg(0x48, 0x00); + writeReg(0x30, 0x20); + + writeReg(0xFF, 0x00); + writeReg(0x30, 0x09); + writeReg(0x54, 0x00); + writeReg(0x31, 0x04); + writeReg(0x32, 0x03); + writeReg(0x40, 0x83); + writeReg(0x46, 0x25); + writeReg(0x60, 0x00); + writeReg(0x27, 0x00); + writeReg(0x50, 0x06); + writeReg(0x51, 0x00); + writeReg(0x52, 0x96); + writeReg(0x56, 0x08); + writeReg(0x57, 0x30); + writeReg(0x61, 0x00); + writeReg(0x62, 0x00); + writeReg(0x64, 0x00); + writeReg(0x65, 0x00); + writeReg(0x66, 0xA0); + + writeReg(0xFF, 0x01); + writeReg(0x22, 0x32); + writeReg(0x47, 0x14); + writeReg(0x49, 0xFF); + writeReg(0x4A, 0x00); + + writeReg(0xFF, 0x00); + writeReg(0x7A, 0x0A); + writeReg(0x7B, 0x00); + writeReg(0x78, 0x21); + + writeReg(0xFF, 0x01); + writeReg(0x23, 0x34); + writeReg(0x42, 0x00); + writeReg(0x44, 0xFF); + writeReg(0x45, 0x26); + writeReg(0x46, 0x05); + writeReg(0x40, 0x40); + writeReg(0x0E, 0x06); + writeReg(0x20, 0x1A); + writeReg(0x43, 0x40); + + writeReg(0xFF, 0x00); + writeReg(0x34, 0x03); + writeReg(0x35, 0x44); + + writeReg(0xFF, 0x01); + writeReg(0x31, 0x04); + writeReg(0x4B, 0x09); + writeReg(0x4C, 0x05); + writeReg(0x4D, 0x04); + + writeReg(0xFF, 0x00); + writeReg(0x44, 0x00); + writeReg(0x45, 0x20); + writeReg(0x47, 0x08); + writeReg(0x48, 0x28); + writeReg(0x67, 0x00); + writeReg(0x70, 0x04); + writeReg(0x71, 0x01); + writeReg(0x72, 0xFE); + writeReg(0x76, 0x00); + writeReg(0x77, 0x00); + + writeReg(0xFF, 0x01); + writeReg(0x0D, 0x01); + + writeReg(0xFF, 0x00); + writeReg(0x80, 0x01); + writeReg(0x01, 0xF8); + + writeReg(0xFF, 0x01); + writeReg(0x8E, 0x01); + writeReg(0x00, 0x01); + writeReg(0xFF, 0x00); + writeReg(0x80, 0x00); + + // -- VL53L0X_load_tuning_settings() end + + // "Set interrupt config to new sample ready" + // -- VL53L0X_SetGpioConfig() begin + + writeReg(SYSTEM_INTERRUPT_CONFIG_GPIO, 0x04); + writeReg(GPIO_HV_MUX_ACTIVE_HIGH, readReg(GPIO_HV_MUX_ACTIVE_HIGH) & ~0x10); // active low + writeReg(SYSTEM_INTERRUPT_CLEAR, 0x01); + + // -- VL53L0X_SetGpioConfig() end + + measurement_timing_budget_us = getMeasurementTimingBudget(); + + // "Disable MSRC and TCC by default" + // MSRC = Minimum Signal Rate Check + // TCC = Target CentreCheck + // -- VL53L0X_SetSequenceStepEnable() begin + + writeReg(SYSTEM_SEQUENCE_CONFIG, 0xE8); + + // -- VL53L0X_SetSequenceStepEnable() end + + // "Recalculate timing budget" + setMeasurementTimingBudget(measurement_timing_budget_us); + + // VL53L0X_StaticInit() end + + // VL53L0X_PerformRefCalibration() begin (VL53L0X_perform_ref_calibration()) + + // -- VL53L0X_perform_vhv_calibration() begin + + writeReg(SYSTEM_SEQUENCE_CONFIG, 0x01); + if (!performSingleRefCalibration(0x40)) { return false; } + + // -- VL53L0X_perform_vhv_calibration() end + + // -- VL53L0X_perform_phase_calibration() begin + + writeReg(SYSTEM_SEQUENCE_CONFIG, 0x02); + if (!performSingleRefCalibration(0x00)) { return false; } + + // -- VL53L0X_perform_phase_calibration() end + + // "restore the previous Sequence Config" + writeReg(SYSTEM_SEQUENCE_CONFIG, 0xE8); + + // VL53L0X_PerformRefCalibration() end + + return true; +} + +// Write an 8-bit register +void VL53L0X::writeReg(uint8_t Reg, uint8_t value) +{ + unsigned char reg[2]; + reg[0]=Reg; reg[1]=value; + I2C1_Write(address, reg, 2); + I2C1_Stop(); + //I2C1_Write(address,reg); + // I2C1_Write(address,value); + //I2C1_Stop(); + // bus->beginTransmission(address); +// bus->write(reg); + // bus->write(value); + // last_status = bus->endTransmission(); +} + +// Write a 16-bit register +void VL53L0X::writeReg16Bit(uint8_t Reg, uint16_t value) +{ + unsigned char reg[3]; + reg[0]=Reg; reg[1]=value >> 8;reg[2]=value; + I2C1_Write(address, reg, 3); + I2C1_Stop(); + + + + +} + +// Write a 32-bit register +void VL53L0X::writeReg32Bit(uint8_t Reg, uint32_t value) +{ + unsigned char reg[5]; + reg[0]=Reg; reg[1]=value >> 24 ;reg[2]=value >> 16; reg[3]=value >> 8 ;reg[4]=value; + I2C1_Write(address, reg, 5); + I2C1_Stop(); + + +} + +// Read an 8-bit register +uint8_t VL53L0X::readReg(uint8_t reg) +{ + + uint8_t value; + + I2C1_Write(address,reg); + I2C1_Read(address,&value,1); + I2C1_Stop(); + + return value; +} + +// Read a 16-bit register +uint16_t VL53L0X::readReg16Bit(uint8_t reg) +{ + uint16_t valueRead; + + I2C1_Write(address,reg); + I2C1_Read(address,&valueRead, sizeof(valueRead)); + I2C1_Stop(); + valueRead = (valueRead << 8) | (valueRead >> 8); + return valueRead; +} + +//// Read a 32-bit register +//uint32_t VL53L0X::readReg32Bit(uint8_t reg) +//{ +// uint32_t valueRead; +// +// I2C1_Write(address,reg); +// I2C1_Read(address,&valueRead, sizeof(valueRead)); +// I2C1_Stop(); +// +//valueRead = (valueRead & 0x0000FFFF) << 16 | (valueRead & 0xFFFF0000) >> 16; +//valueRead = (valueRead& 0x00FF00FF) << 8 | (valueRead & 0xFF00FF00) >> 8; +// return valueRead; +// +//} + +// Write an arbitrary number of bytes from the given array to the sensor, +// starting at the given register +void VL53L0X::writeMulti(uint8_t reg, uint8_t const * src, uint8_t count) +{ + // const int cnt = count+1; +// unsigned char Reg[32]; +// Reg[0]=reg; +// +// for (int i = 1;i 0) +// { +// I2C1_Write(address, *(src++)); +// +// } +I2C1_Stop(); +return; +} + +// Read an arbitrary number of bytes from the sensor, starting at the given +// register, into the given array +void VL53L0X::readMulti(uint8_t reg, uint8_t * dst, uint8_t count) +{ + I2C1_Write(address, reg); + + I2C1_Read(address, dst, count); + + I2C1_Stop(); + return; +} + +// Set the return signal rate limit check value in units of MCPS (mega counts +// per second). "This represents the amplitude of the signal reflected from the +// target and detected by the device"; setting this limit presumably determines +// the minimum measurement necessary for the sensor to report a valid reading. +// Setting a lower limit increases the potential range of the sensor but also +// seems to increase the likelihood of getting an inaccurate reading because of +// unwanted reflections from objects other than the intended target. +// Defaults to 0.25 MCPS as initialized by the ST API and this library. +bool VL53L0X::setSignalRateLimit(float limit_Mcps) +{ + if (limit_Mcps < 0 || limit_Mcps > 511.99) { return false; } + + // Q9.7 fixed point format (9 integer bits, 7 fractional bits) + writeReg16Bit(FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT, limit_Mcps * (1 << 7)); + return true; +} + +// Get the return signal rate limit check value in MCPS +float VL53L0X::getSignalRateLimit() +{ + return (float)readReg16Bit(FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT) / (1 << 7); +} + +// Set the measurement timing budget in microseconds, which is the time allowed +// for one measurement; the ST API and this library take care of splitting the +// timing budget among the sub-steps in the ranging sequence. A longer timing +// budget allows for more accurate measurements. Increasing the budget by a +// factor of N decreases the range measurement standard deviation by a factor of +// sqrt(N). Defaults to about 33 milliseconds; the minimum is 20 ms. +// based on VL53L0X_set_measurement_timing_budget_micro_seconds() +bool VL53L0X::setMeasurementTimingBudget(uint32_t budget_us) +{ + SequenceStepEnables enables; + SequenceStepTimeouts timeouts; + + uint16_t const StartOverhead = 1910; + uint16_t const EndOverhead = 960; + uint16_t const MsrcOverhead = 660; + uint16_t const TccOverhead = 590; + uint16_t const DssOverhead = 690; + uint16_t const PreRangeOverhead = 660; + uint16_t const FinalRangeOverhead = 550; + + uint32_t used_budget_us = StartOverhead + EndOverhead; + + getSequenceStepEnables(&enables); + getSequenceStepTimeouts(&enables, &timeouts); + + if (enables.tcc) + { + used_budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead); + } + + if (enables.dss) + { + used_budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead); + } + else if (enables.msrc) + { + used_budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead); + } + + if (enables.pre_range) + { + used_budget_us += (timeouts.pre_range_us + PreRangeOverhead); + } + + if (enables.final_range) + { + used_budget_us += FinalRangeOverhead; + + // "Note that the final range timeout is determined by the timing + // budget and the sum of all other timeouts within the sequence. + // If there is no room for the final range timeout, then an error + // will be set. Otherwise the remaining time will be applied to + // the final range." + + if (used_budget_us > budget_us) + { + // "Requested timeout too big." + return false; + } + + uint32_t final_range_timeout_us = budget_us - used_budget_us; + + // set_sequence_step_timeout() begin + // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE) + + // "For the final range timeout, the pre-range timeout + // must be added. To do this both final and pre-range + // timeouts must be expressed in macro periods MClks + // because they have different vcsel periods." + + uint32_t final_range_timeout_mclks = + timeoutMicrosecondsToMclks(final_range_timeout_us, + timeouts.final_range_vcsel_period_pclks); + + if (enables.pre_range) + { + final_range_timeout_mclks += timeouts.pre_range_mclks; + } + + writeReg16Bit(FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI, + encodeTimeout(final_range_timeout_mclks)); + + // set_sequence_step_timeout() end + + measurement_timing_budget_us = budget_us; // store for internal reuse + } + return true; +} + +// Get the measurement timing budget in microseconds +// based on VL53L0X_get_measurement_timing_budget_micro_seconds() +// in us +uint32_t VL53L0X::getMeasurementTimingBudget() +{ + SequenceStepEnables enables; + SequenceStepTimeouts timeouts; + + uint16_t const StartOverhead = 1910; + uint16_t const EndOverhead = 960; + uint16_t const MsrcOverhead = 660; + uint16_t const TccOverhead = 590; + uint16_t const DssOverhead = 690; + uint16_t const PreRangeOverhead = 660; + uint16_t const FinalRangeOverhead = 550; + + // "Start and end overhead times always present" + uint32_t budget_us = StartOverhead + EndOverhead; + + getSequenceStepEnables(&enables); + getSequenceStepTimeouts(&enables, &timeouts); + + if (enables.tcc) + { + budget_us += (timeouts.msrc_dss_tcc_us + TccOverhead); + } + + if (enables.dss) + { + budget_us += 2 * (timeouts.msrc_dss_tcc_us + DssOverhead); + } + else if (enables.msrc) + { + budget_us += (timeouts.msrc_dss_tcc_us + MsrcOverhead); + } + + if (enables.pre_range) + { + budget_us += (timeouts.pre_range_us + PreRangeOverhead); + } + + if (enables.final_range) + { + budget_us += (timeouts.final_range_us + FinalRangeOverhead); + } + + measurement_timing_budget_us = budget_us; // store for internal reuse + return budget_us; +} + +// Set the VCSEL (vertical cavity surface emitting laser) pulse period for the +// given period type (pre-range or final range) to the given value in PCLKs. +// Longer periods seem to increase the potential range of the sensor. +// Valid values are (even numbers only): +// pre: 12 to 18 (initialized default: 14) +// final: 8 to 14 (initialized default: 10) +// based on VL53L0X_set_vcsel_pulse_period() +bool VL53L0X::setVcselPulsePeriod(vcselPeriodType type, uint8_t period_pclks) +{ + uint8_t vcsel_period_reg = encodeVcselPeriod(period_pclks); + + SequenceStepEnables enables; + SequenceStepTimeouts timeouts; + + getSequenceStepEnables(&enables); + getSequenceStepTimeouts(&enables, &timeouts); + + // "Apply specific settings for the requested clock period" + // "Re-calculate and apply timeouts, in macro periods" + + // "When the VCSEL period for the pre or final range is changed, + // the corresponding timeout must be read from the device using + // the current VCSEL period, then the new VCSEL period can be + // applied. The timeout then must be written back to the device + // using the new VCSEL period. + // + // For the MSRC timeout, the same applies - this timeout being + // dependant on the pre-range vcsel period." + + + if (type == VcselPeriodPreRange) + { + // "Set phase check limits" + switch (period_pclks) + { + case 12: + writeReg(PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x18); + break; + + case 14: + writeReg(PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x30); + break; + + case 16: + writeReg(PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x40); + break; + + case 18: + writeReg(PRE_RANGE_CONFIG_VALID_PHASE_HIGH, 0x50); + break; + + default: + // invalid period + return false; + } + writeReg(PRE_RANGE_CONFIG_VALID_PHASE_LOW, 0x08); + + // apply new VCSEL period + writeReg(PRE_RANGE_CONFIG_VCSEL_PERIOD, vcsel_period_reg); + + // update timeouts + + // set_sequence_step_timeout() begin + // (SequenceStepId == VL53L0X_SEQUENCESTEP_PRE_RANGE) + + uint16_t new_pre_range_timeout_mclks = + timeoutMicrosecondsToMclks(timeouts.pre_range_us, period_pclks); + + writeReg16Bit(PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI, + encodeTimeout(new_pre_range_timeout_mclks)); + + // set_sequence_step_timeout() end + + // set_sequence_step_timeout() begin + // (SequenceStepId == VL53L0X_SEQUENCESTEP_MSRC) + + uint16_t new_msrc_timeout_mclks = + timeoutMicrosecondsToMclks(timeouts.msrc_dss_tcc_us, period_pclks); + + writeReg(MSRC_CONFIG_TIMEOUT_MACROP, + (new_msrc_timeout_mclks > 256) ? 255 : (new_msrc_timeout_mclks - 1)); + + // set_sequence_step_timeout() end + } + else if (type == VcselPeriodFinalRange) + { + switch (period_pclks) + { + case 8: + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x10); + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_LOW, 0x08); + writeReg(GLOBAL_CONFIG_VCSEL_WIDTH, 0x02); + writeReg(ALGO_PHASECAL_CONFIG_TIMEOUT, 0x0C); + writeReg(0xFF, 0x01); + writeReg(ALGO_PHASECAL_LIM, 0x30); + writeReg(0xFF, 0x00); + break; + + case 10: + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x28); + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_LOW, 0x08); + writeReg(GLOBAL_CONFIG_VCSEL_WIDTH, 0x03); + writeReg(ALGO_PHASECAL_CONFIG_TIMEOUT, 0x09); + writeReg(0xFF, 0x01); + writeReg(ALGO_PHASECAL_LIM, 0x20); + writeReg(0xFF, 0x00); + break; + + case 12: + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x38); + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_LOW, 0x08); + writeReg(GLOBAL_CONFIG_VCSEL_WIDTH, 0x03); + writeReg(ALGO_PHASECAL_CONFIG_TIMEOUT, 0x08); + writeReg(0xFF, 0x01); + writeReg(ALGO_PHASECAL_LIM, 0x20); + writeReg(0xFF, 0x00); + break; + + case 14: + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x48); + writeReg(FINAL_RANGE_CONFIG_VALID_PHASE_LOW, 0x08); + writeReg(GLOBAL_CONFIG_VCSEL_WIDTH, 0x03); + writeReg(ALGO_PHASECAL_CONFIG_TIMEOUT, 0x07); + writeReg(0xFF, 0x01); + writeReg(ALGO_PHASECAL_LIM, 0x20); + writeReg(0xFF, 0x00); + break; + + default: + // invalid period + return false; + } + + // apply new VCSEL period + writeReg(FINAL_RANGE_CONFIG_VCSEL_PERIOD, vcsel_period_reg); + + // update timeouts + + // set_sequence_step_timeout() begin + // (SequenceStepId == VL53L0X_SEQUENCESTEP_FINAL_RANGE) + + // "For the final range timeout, the pre-range timeout + // must be added. To do this both final and pre-range + // timeouts must be expressed in macro periods MClks + // because they have different vcsel periods." + + uint16_t new_final_range_timeout_mclks = + timeoutMicrosecondsToMclks(timeouts.final_range_us, period_pclks); + + if (enables.pre_range) + { + new_final_range_timeout_mclks += timeouts.pre_range_mclks; + } + + writeReg16Bit(FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI, + encodeTimeout(new_final_range_timeout_mclks)); + + // set_sequence_step_timeout end + } + else + { + // invalid type + return false; + } + + // "Finally, the timing budget must be re-applied" + + setMeasurementTimingBudget(measurement_timing_budget_us); + + // "Perform the phase calibration. This is needed after changing on vcsel period." + // VL53L0X_perform_phase_calibration() begin + + uint8_t sequence_config = readReg(SYSTEM_SEQUENCE_CONFIG); + writeReg(SYSTEM_SEQUENCE_CONFIG, 0x02); + performSingleRefCalibration(0x0); + writeReg(SYSTEM_SEQUENCE_CONFIG, sequence_config); + + // VL53L0X_perform_phase_calibration() end + + return true; +} + +// Get the VCSEL pulse period in PCLKs for the given period type. +// based on VL53L0X_get_vcsel_pulse_period() +uint8_t VL53L0X::getVcselPulsePeriod(vcselPeriodType type) +{ + if (type == VcselPeriodPreRange) + { + return decodeVcselPeriod(readReg(PRE_RANGE_CONFIG_VCSEL_PERIOD)); + } + else if (type == VcselPeriodFinalRange) + { + return decodeVcselPeriod(readReg(FINAL_RANGE_CONFIG_VCSEL_PERIOD)); + } + else { return 255; } +} + +// Start continuous ranging measurements. If period_ms (optional) is 0 or not +// given, continuous back-to-back mode is used (the sensor takes measurements as +// often as possible); otherwise, continuous timed mode is used, with the given +// inter-measurement period in milliseconds determining how often the sensor +// takes a measurement. +// based on VL53L0X_StartMeasurement() +void VL53L0X::startContinuous(uint32_t period_ms) +{ + writeReg(0x80, 0x01); + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + writeReg(0x91, stop_variable); + writeReg(0x00, 0x01); + writeReg(0xFF, 0x00); + writeReg(0x80, 0x00); + + if (period_ms != 0) + { + // continuous timed mode + + // VL53L0X_SetInterMeasurementPeriodMilliSeconds() begin + + uint16_t osc_calibrate_val = readReg16Bit(OSC_CALIBRATE_VAL); + + if (osc_calibrate_val != 0) + { + period_ms *= osc_calibrate_val; + } + + writeReg32Bit(SYSTEM_INTERMEASUREMENT_PERIOD, period_ms); + + // VL53L0X_SetInterMeasurementPeriodMilliSeconds() end + + writeReg(SYSRANGE_START, 0x04); // VL53L0X_REG_SYSRANGE_MODE_TIMED + } + else + { + // continuous back-to-back mode + writeReg(SYSRANGE_START, 0x02); // VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK + } +} + +// Stop continuous measurements +// based on VL53L0X_StopMeasurement() +void VL53L0X::stopContinuous() +{ + writeReg(SYSRANGE_START, 0x01); // VL53L0X_REG_SYSRANGE_MODE_SINGLESHOT + + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + writeReg(0x91, 0x00); + writeReg(0x00, 0x01); + writeReg(0xFF, 0x00); +} + + + + + bool VL53L0X::isRangeReady() { + return (readReg(RESULT_INTERRUPT_STATUS) & 0x07); + } + + uint16_t VL53L0X::readRange() { + uint16_t range = readReg16Bit(RESULT_RANGE_STATUS + 10); + writeReg(SYSTEM_INTERRUPT_CLEAR, 0x01); + return range; + } + + +// Returns a range reading in millimeters when continuous mode is active +// (readRangeSingleMillimeters() also calls this function after starting a +// single-shot range measurement) +uint16_t VL53L0X::readRangeContinuousMillimeters() +{ + startTimeout(); + while ((readReg(RESULT_INTERRUPT_STATUS) & 0x07) == 0) + { + if (checkTimeoutExpired()) + { + did_timeout = true; + return 65535; + } + } + + // assumptions: Linearity Corrective Gain is 1000 (default); + // fractional ranging is not enabled + uint16_t range = readReg16Bit(RESULT_RANGE_STATUS + 10); + + writeReg(SYSTEM_INTERRUPT_CLEAR, 0x01); + + return range; +} + +// Performs a single-shot range measurement and returns the reading in +// millimeters +// based on VL53L0X_PerformSingleRangingMeasurement() +uint16_t VL53L0X::readRangeSingleMillimeters() +{ + writeReg(0x80, 0x01); + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + writeReg(0x91, stop_variable); + writeReg(0x00, 0x01); + writeReg(0xFF, 0x00); + writeReg(0x80, 0x00); + + writeReg(SYSRANGE_START, 0x01); + + // "Wait until start bit has been cleared" + startTimeout(); + while (readReg(SYSRANGE_START) & 0x01) + { + if (checkTimeoutExpired()) + { + did_timeout = true; + return 65535; + } + } + + return readRangeContinuousMillimeters(); +} + +// Did a timeout occur in one of the read functions since the last call to +// timeoutOccurred()? +bool VL53L0X::timeoutOccurred() +{ + bool tmp = did_timeout; + did_timeout = false; + return tmp; +} + +// Private Methods ///////////////////////////////////////////////////////////// + +// Get reference SPAD (single photon avalanche diode) count and type +// based on VL53L0X_get_info_from_device(), +// but only gets reference SPAD count and type +bool VL53L0X::getSpadInfo(uint8_t * count, bool * type_is_aperture) +{ + uint8_t tmp; + + writeReg(0x80, 0x01); + writeReg(0xFF, 0x01); + writeReg(0x00, 0x00); + + writeReg(0xFF, 0x06); + writeReg(0x83, readReg(0x83) | 0x04); + writeReg(0xFF, 0x07); + writeReg(0x81, 0x01); + + writeReg(0x80, 0x01); + + writeReg(0x94, 0x6b); + writeReg(0x83, 0x00); + startTimeout(); + while (readReg(0x83) == 0x00) + { + if (checkTimeoutExpired()) { return false; } + } + writeReg(0x83, 0x01); + tmp = readReg(0x92); + + *count = tmp & 0x7f; + *type_is_aperture = (tmp >> 7) & 0x01; + + writeReg(0x81, 0x00); + writeReg(0xFF, 0x06); + writeReg(0x83, readReg(0x83) & ~0x04); + writeReg(0xFF, 0x01); + writeReg(0x00, 0x01); + + writeReg(0xFF, 0x00); + writeReg(0x80, 0x00); + + return true; +} + +// Get sequence step enables +// based on VL53L0X_GetSequenceStepEnables() +void VL53L0X::getSequenceStepEnables(SequenceStepEnables * enables) +{ + uint8_t sequence_config = readReg(SYSTEM_SEQUENCE_CONFIG); + + enables->tcc = (sequence_config >> 4) & 0x1; + enables->dss = (sequence_config >> 3) & 0x1; + enables->msrc = (sequence_config >> 2) & 0x1; + enables->pre_range = (sequence_config >> 6) & 0x1; + enables->final_range = (sequence_config >> 7) & 0x1; +} + +// Get sequence step timeouts +// based on get_sequence_step_timeout(), +// but gets all timeouts instead of just the requested one, and also stores +// intermediate values +void VL53L0X::getSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts) +{ + timeouts->pre_range_vcsel_period_pclks = getVcselPulsePeriod(VcselPeriodPreRange); + + timeouts->msrc_dss_tcc_mclks = readReg(MSRC_CONFIG_TIMEOUT_MACROP) + 1; + timeouts->msrc_dss_tcc_us = + timeoutMclksToMicroseconds(timeouts->msrc_dss_tcc_mclks, + timeouts->pre_range_vcsel_period_pclks); + + timeouts->pre_range_mclks = + decodeTimeout(readReg16Bit(PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI)); + timeouts->pre_range_us = + timeoutMclksToMicroseconds(timeouts->pre_range_mclks, + timeouts->pre_range_vcsel_period_pclks); + + timeouts->final_range_vcsel_period_pclks = getVcselPulsePeriod(VcselPeriodFinalRange); + + timeouts->final_range_mclks = + decodeTimeout(readReg16Bit(FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI)); + + if (enables->pre_range) + { + timeouts->final_range_mclks -= timeouts->pre_range_mclks; + } + + timeouts->final_range_us = + timeoutMclksToMicroseconds(timeouts->final_range_mclks, + timeouts->final_range_vcsel_period_pclks); +} + +// Decode sequence step timeout in MCLKs from register value +// based on VL53L0X_decode_timeout() +// Note: the original function returned a uint32_t, but the return value is +// always stored in a uint16_t. +uint16_t VL53L0X::decodeTimeout(uint16_t reg_val) +{ + // format: "(LSByte * 2^MSByte) + 1" + return (uint16_t)((reg_val & 0x00FF) << + (uint16_t)((reg_val & 0xFF00) >> 8)) + 1; +} + +// Encode sequence step timeout register value from timeout in MCLKs +// based on VL53L0X_encode_timeout() +uint16_t VL53L0X::encodeTimeout(uint32_t timeout_mclks) +{ + // format: "(LSByte * 2^MSByte) + 1" + + uint32_t ls_byte = 0; + uint16_t ms_byte = 0; + + if (timeout_mclks > 0) + { + ls_byte = timeout_mclks - 1; + + while ((ls_byte & 0xFFFFFF00) > 0) + { + ls_byte >>= 1; + ms_byte++; + } + + return (ms_byte << 8) | (ls_byte & 0xFF); + } + else { return 0; } +} + +// Convert sequence step timeout from MCLKs to microseconds with given VCSEL period in PCLKs +// based on VL53L0X_calc_timeout_us() +uint32_t VL53L0X::timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks) +{ + uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks); + + return ((timeout_period_mclks * macro_period_ns) + 500) / 1000; +} + +// Convert sequence step timeout from microseconds to MCLKs with given VCSEL period in PCLKs +// based on VL53L0X_calc_timeout_mclks() +uint32_t VL53L0X::timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks) +{ + uint32_t macro_period_ns = calcMacroPeriod(vcsel_period_pclks); + + return (((timeout_period_us * 1000) + (macro_period_ns / 2)) / macro_period_ns); +} + + +// based on VL53L0X_perform_single_ref_calibration() +bool VL53L0X::performSingleRefCalibration(uint8_t vhv_init_byte) +{ + writeReg(SYSRANGE_START, 0x01 | vhv_init_byte); // VL53L0X_REG_SYSRANGE_MODE_START_STOP + + startTimeout(); + while ((readReg(RESULT_INTERRUPT_STATUS) & 0x07) == 0) + { + if (checkTimeoutExpired()) { return false; } + } + + writeReg(SYSTEM_INTERRUPT_CLEAR, 0x01); + + writeReg(SYSRANGE_START, 0x00); + + return true; +} \ No newline at end of file diff --git a/drv/vl53l0x.h b/drv/vl53l0x.h new file mode 100644 index 0000000..d308e0b --- /dev/null +++ b/drv/vl53l0x.h @@ -0,0 +1,186 @@ +#ifndef VL53L0X_h +#define VL53L0X_h + +#include +#include "tick.h" + +class VL53L0X +{ + public: + // register addresses from API vl53l0x_device.h (ordered as listed there) + enum regAddr + { + SYSRANGE_START = 0x00, + + SYSTEM_THRESH_HIGH = 0x0C, + SYSTEM_THRESH_LOW = 0x0E, + + SYSTEM_SEQUENCE_CONFIG = 0x01, + SYSTEM_RANGE_CONFIG = 0x09, + SYSTEM_INTERMEASUREMENT_PERIOD = 0x04, + + SYSTEM_INTERRUPT_CONFIG_GPIO = 0x0A, + + GPIO_HV_MUX_ACTIVE_HIGH = 0x84, + + SYSTEM_INTERRUPT_CLEAR = 0x0B, + + RESULT_INTERRUPT_STATUS = 0x13, + RESULT_RANGE_STATUS = 0x14, + + RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN = 0xBC, + RESULT_CORE_RANGING_TOTAL_EVENTS_RTN = 0xC0, + RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF = 0xD0, + RESULT_CORE_RANGING_TOTAL_EVENTS_REF = 0xD4, + RESULT_PEAK_SIGNAL_RATE_REF = 0xB6, + + ALGO_PART_TO_PART_RANGE_OFFSET_MM = 0x28, + + I2C_SLAVE_DEVICE_ADDRESS = 0x8A, + + MSRC_CONFIG_CONTROL = 0x60, + + PRE_RANGE_CONFIG_MIN_SNR = 0x27, + PRE_RANGE_CONFIG_VALID_PHASE_LOW = 0x56, + PRE_RANGE_CONFIG_VALID_PHASE_HIGH = 0x57, + PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT = 0x64, + + FINAL_RANGE_CONFIG_MIN_SNR = 0x67, + FINAL_RANGE_CONFIG_VALID_PHASE_LOW = 0x47, + FINAL_RANGE_CONFIG_VALID_PHASE_HIGH = 0x48, + FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT = 0x44, + + PRE_RANGE_CONFIG_SIGMA_THRESH_HI = 0x61, + PRE_RANGE_CONFIG_SIGMA_THRESH_LO = 0x62, + + PRE_RANGE_CONFIG_VCSEL_PERIOD = 0x50, + PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI = 0x51, + PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO = 0x52, + + SYSTEM_HISTOGRAM_BIN = 0x81, + HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT = 0x33, + HISTOGRAM_CONFIG_READOUT_CTRL = 0x55, + + FINAL_RANGE_CONFIG_VCSEL_PERIOD = 0x70, + FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI = 0x71, + FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO = 0x72, + CROSSTALK_COMPENSATION_PEAK_RATE_MCPS = 0x20, + + MSRC_CONFIG_TIMEOUT_MACROP = 0x46, + + SOFT_RESET_GO2_SOFT_RESET_N = 0xBF, + IDENTIFICATION_MODEL_ID = 0xC0, + IDENTIFICATION_REVISION_ID = 0xC2, + + OSC_CALIBRATE_VAL = 0xF8, + + GLOBAL_CONFIG_VCSEL_WIDTH = 0x32, + GLOBAL_CONFIG_SPAD_ENABLES_REF_0 = 0xB0, + GLOBAL_CONFIG_SPAD_ENABLES_REF_1 = 0xB1, + GLOBAL_CONFIG_SPAD_ENABLES_REF_2 = 0xB2, + GLOBAL_CONFIG_SPAD_ENABLES_REF_3 = 0xB3, + GLOBAL_CONFIG_SPAD_ENABLES_REF_4 = 0xB4, + GLOBAL_CONFIG_SPAD_ENABLES_REF_5 = 0xB5, + + GLOBAL_CONFIG_REF_EN_START_SELECT = 0xB6, + DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD = 0x4E, + DYNAMIC_SPAD_REF_EN_START_OFFSET = 0x4F, + POWER_MANAGEMENT_GO1_POWER_FORCE = 0x80, + + VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV = 0x89, + + ALGO_PHASECAL_LIM = 0x30, + ALGO_PHASECAL_CONFIG_TIMEOUT = 0x30, + }; + + enum vcselPeriodType { VcselPeriodPreRange, VcselPeriodFinalRange }; + + uint8_t last_status; // status of last I2C transmission + + VL53L0X(); + + + + void setAddress(uint8_t new_addr); + inline uint8_t getAddress() { return address; } + + bool init(bool io_2v8 = true); + + void writeReg(uint8_t reg, uint8_t value); + void writeReg16Bit(uint8_t reg, uint16_t value); + void writeReg32Bit(uint8_t reg, uint32_t value); + uint8_t readReg(uint8_t reg); + uint16_t readReg16Bit(uint8_t reg); + uint32_t readReg32Bit(uint8_t reg); + + void writeMulti(uint8_t reg, uint8_t const * src, uint8_t count); + void readMulti(uint8_t reg, uint8_t * dst, uint8_t count); + + bool setSignalRateLimit(float limit_Mcps); + float getSignalRateLimit(); + + bool setMeasurementTimingBudget(uint32_t budget_us); + uint32_t getMeasurementTimingBudget(); + + bool setVcselPulsePeriod(vcselPeriodType type, uint8_t period_pclks); + uint8_t getVcselPulsePeriod(vcselPeriodType type); + + void startContinuous(uint32_t period_ms = 0); + void stopContinuous(); + uint16_t readRangeContinuousMillimeters(); + uint16_t readRangeSingleMillimeters(); + + + bool isRangeReady(); + uint16_t readRange(); + + inline void setTimeout(uint16_t timeout) { io_timeout = timeout; } + inline uint16_t getTimeout() { return io_timeout; } + bool timeoutOccurred(); + + private: + // TCC: Target CentreCheck + // MSRC: Minimum Signal Rate Check + // DSS: Dynamic Spad Selection + + struct SequenceStepEnables + { + bool tcc, msrc, dss, pre_range, final_range; + }; + + struct SequenceStepTimeouts + { + uint16_t pre_range_vcsel_period_pclks, final_range_vcsel_period_pclks; + + uint16_t msrc_dss_tcc_mclks, pre_range_mclks, final_range_mclks; + uint32_t msrc_dss_tcc_us, pre_range_us, final_range_us; + }; + + + uint8_t address; + uint16_t io_timeout; + bool did_timeout; + uint16_t timeout_start_ms; + + uint8_t stop_variable; // read by init and used when starting measurement; is StopVariable field of VL53L0X_DevData_t structure in API + uint32_t measurement_timing_budget_us; + + bool getSpadInfo(uint8_t * count, bool * type_is_aperture); + + void getSequenceStepEnables(SequenceStepEnables * enables); + void getSequenceStepTimeouts(SequenceStepEnables const * enables, SequenceStepTimeouts * timeouts); + + bool performSingleRefCalibration(uint8_t vhv_init_byte); + + static uint16_t decodeTimeout(uint16_t value); + static uint16_t encodeTimeout(uint32_t timeout_mclks); + static uint32_t timeoutMclksToMicroseconds(uint16_t timeout_period_mclks, uint8_t vcsel_period_pclks); + static uint32_t timeoutMicrosecondsToMclks(uint32_t timeout_period_us, uint8_t vcsel_period_pclks); + + + +}; + +#endif + + diff --git a/main.cpp b/main.cpp new file mode 100644 index 0000000..68a4948 --- /dev/null +++ b/main.cpp @@ -0,0 +1,587 @@ +#include +#include +#include + +#include "stm32g4xx.h" + +#include "gpio.h" +#include "led.h" +#include "ori.h" +#include "bar.h" +#include "eep.h" +#include "tim.h" +#include "pwm.h" +#include "tele.h" +#include "med.h" +#include "tick.h" + +#include "sbus.h" +#include "iwdg.h" +#include "pid.h" +#include "uart.h" +#include "gps.h" + +#include "laser.h" +#include "flow.h" + +#include "imu.h" + +#include "mot.h" +#include "move.h" + +#include "prot.h" + + +static const float PI = 3.14159265359f; +static const float TO_RAD = PI/180.0f; + +#define TELE_TIMER 10 // ms +#define LED_TIMER 100 // ms +#define JOY_TIMER 200 // ms + +#define LOG_TIMER 5 // ms + +#define PWM_FREQ 100 // Hz + +#define MAIN_UPDATE_FREQ 100 // Hz +#define MAIN_UPDATE_PRIORITY 2 + +PID_Data PID_X = { -1000, 1000, {-500, 500, 1}, {-50, 50, 0.0}, {-500, 500, 0.020} }; +PID_Data PID_Y = { -1000, 1000, {-500, 500, 1}, {-50, 50, 0.0}, {-500, 500, 0.020} }; +PID_Data PID_Z = { -1000, 1000, {-500, 500, 1}, {-50, 50, 0.0}, {-500, 500, 0.03} }; + +short Joy_throt = 0; // Gass +short Joy_pitch = 0; // Y +short Joy_roll = 0; // X +short Joy_yaw = 0; // Z + +short Main_PWM[4]{ 0, 0, 0, 0 }; + +float Main_dXYZ[3]={0, 0, 0}; +bool MainValid=false; + +//IBUS_Data Joypad; +SBUS_Data Joypad; +bool JoypadOff; + +IMU_Data DataIMU; +BAR_Data DataBAR; +MAG_Data DataMAG = {0,0,0}; + + +bool imu_ready=false, bar_ready=false, mag_ready=false; + + + +SBUS_Data rc; +unsigned char fs; + +short PWM_NONE = 0; + + +int m= 0; +unsigned short dist_mm; + uint16_t dist ; + float meters; + + short dx, dy; + unsigned char qality; + + +void DoneProcIMU(IMU_Data& Data) +{ + DataIMU=Data; + imu_ready=true; + if(bar_ready && mag_ready) NVIC_SetPendingIRQ(TIM7_IRQn); +} + +void DoneProcBAR(bool Ready, BAR_Data& Data) +{ + //if(!Ready) { BAR_GetAsunc(DoneProcBAR); return; } + DataBAR=Data; + bar_ready=true; + if(imu_ready && mag_ready) NVIC_SetPendingIRQ(TIM7_IRQn); +} + + + +short test_pow[3]; + +Point DataGPS{0,0,0}; + +short test_p=0, test_r=0; + +Vec3 test_iner={0,0,0}; + +float range = 0; + + void Main_Update() +{ + IMU_Get(DataIMU); + + DataIMU.Bar=BAR_GetData(&DataIMU.Tmp); + //if(!mag_ready) MAG_GetAsunc(DoneProcMAG); + + //if(!imu_ready || !bar_ready || !mag_ready) return; +//if(!imu_ready || !bar_ready) return; + + + + PingIWDG(); + + imu_ready=false; + bar_ready=false; + mag_ready=false; + + DataIMU.Mag={DataMAG.X, DataMAG.Y, DataMAG.Z}; + + ORI_Get(DataORI, MAIN_UPDATE_FREQ, DataIMU, DataBAR); + + static Vec3 flow; + + static long timer=0; + if(timer>=4) + { + if (isRangeReady()) + { + range = getRange(); + } + + bool move=FLOW_GetMotion(&dx, &dy, &qality); + flow=Motion({DataORI.SinX, DataORI.SinY, DataORI.CosZ}, move, dx, dy, range, 0); + timer=0; + + if(range<0.15f) + { + Main_StatusMode=STATUS_MODE::on_ground; + Main_SysMode=SYS_MODE::hold; + } + } + else timer++; + + short yaw=(DataORI.Yaw-Joy_yaw)+180; + if(yaw<0) yaw+=360; + if(yaw>360) yaw-=360; + static short pov_z; + pov_z = (short)(PID_Update(180, yaw, PID_Z, DataORI.Gyr.Z)); + + static float height; + static Point zero; + + + float altitude; + Point coord; + bool valid; + bool ready; + + ready=GPS_GetCoordinates(DataGPS, valid); + valid=1; + + /*MainValid=(last && valid); + + if(MainValid) + { + if(Joypad.SWB>JOY_MID) { zero=coord; height=altitude; ready=true; } + GPS_LocalDistance(zero, coord, Main_dXYZ[0], Main_dXYZ[1]); + Main_dXYZ[2]=height-altitude; + }*/ + + //GPS_Navigation(MainValid, DataORI, Main_dXYZ); + + //if(Joypad.SWAJOY_MID+50 || Joypad.XJOY_MID+50 || Joypad.YJOY_MID) + { + MainFlyMode=MAIN_FLY_MODE::STOP; + + /*if(Joypad.SWB>JOY_MID) + { + MainFlyMode=MAIN_FLY_MODE::STOP; + } + else + { + //PointGPS=DataGPS; + //PointGPS.Altitude+=3; + }*/ + + if(MainFlyMode==MAIN_FLY_MODE::WAIT) + { + if(autopilot==true) { PWM_SetAll(900); return; } + } + + if(MainFlyMode==MAIN_FLY_MODE::START) + { + if(autopilot==true) { PWM_SetAll(1100); return; } + } + + if(MainFlyMode==MAIN_FLY_MODE::STOP) + { + Main_StatusMode=STATUS_MODE::landing; + Main_SysMode=SYS_MODE::land; + + if(autopilot==true) + { + //throt=500; + + float shift=0.5f+flow.z; + + float fx=-flow.x*shift; + float fy=-flow.y*shift; + + mx+=fx; + my+=fy; + + test_iner.x=mx/1000; + test_iner.y=my/1000; + test_iner.z=flow.z; + + pitch=my*0.005f; + roll=mx*0.005f; + + pitch+=fy*0.4f; + roll+=fx*0.4f; + + if(pitch>+20) pitch=+20; + if(pitch<-20) pitch=-20; + + if(roll>+20) roll=+20; + if(roll<-20) roll=-20; + + Joy_pitch=pitch; + Joy_roll=roll; + + static long add_power=0; + add_power=(heigh-flow.z*1000.0f)*0.1f; + + if(add_power>+500) add_power=+500; + if(add_power<-500) add_power=-500; + + throt+=add_power; + + static int count=0; + static float last_h=0, delta_h=0; + if(count>=9) + { + delta_h=(last_h-flow.z*1000.0f); + + last_h=flow.z*1000.0f; + + count=0; + } + else count++; + + if(delta_h>+200) delta_h=+200; + if(delta_h<-200) delta_h=-200; + + throt+=delta_h*1.0f; + + if(throt>800) throt=800; + if(throt<100) throt=100; + + + if(Joypad.SWB>JOY_MID) + { + if(flow.z>0.3f) + heigh-=3.0f; + else + heigh-=10.0f; + } + if(heigh<-5000) + { + heigh=-5000; + MainFlyMode=MAIN_FLY_MODE::START; + } + } + } + else + { + heigh=flow.z*1000.0f; + mx=0; my=0; + } + + if(MainFlyMode==MAIN_FLY_MODE::FLY) + { + + Main_StatusMode=STATUS_MODE::fly; + Main_SysMode=SYS_MODE::auto_mode; + + if((autopilot==true) && (ready && valid)) + { + //throt=500; + + static float last_a=0, delta_a=0; + long power=(PointGPS.Altitude-DataGPS.Altitude)*100.0f; + + + + static int count=0; + + if(count>1) + { + delta_a=(DataGPS.Altitude-last_a); + + last_a=DataGPS.Altitude; + + count=0; + } + else count++; + + power+=delta_a*50.0f; + + if(power>+500) power=+500; + if(power<-500) power=-500; + + //throt+=power; + + //if(throt<100) throt=100; + } + + if((autopilot==true) && (ready && valid)) + { + static float delta_x=0, delta_y=0; + static float ldx=0, ldy=0; + + float dx, dy; + + GPS_LocalDistance(PointGPS, DataGPS, dx, dy); + + dx=dx; + dy=-dy; + + + pitch=dy*10.0f; + roll=dx*10.0f; + + if(pitch>+20) pitch=+20; + if(pitch<-20) pitch=-20; + + if(roll>+20) roll=+20; + if(roll<-20) roll=-20; + + static int count=0; + + if(count>1) + { + delta_x=(delta_x+(dx-ldx))/2.0f; + delta_y=(delta_y+(dy-ldy))/2.0f; + + ldx=dx; + ldy=dy; + + count=0; + } + else count++; + + //pitch+=delta_y*10.0f; + //roll+=delta_x*10.0f; + + if(pitch>+20) pitch=+20; + if(pitch<-20) pitch=-20; + + if(roll>+20) roll=+20; + if(roll<-20) roll=-20; + + test_p=pitch; + test_r=roll; + + //Vec3 v = RotateToZ({(float)pitch, (float)roll, 0}, false); + //pitch=v.x; roll=v.y; + + Joy_pitch=pitch; + Joy_roll=roll; + } + + if(autopilot==true) + { + Joy_pitch=test_p; + Joy_roll=test_r; + } + } + } + else + { + mx=0; my=0; + heigh=flow.z*1000.0f; + MainFlyMode=MAIN_FLY_MODE::WAIT; + autopilot=true; + } + + short pov_x = (short)(PID_Update(Joy_pitch, DataORI.Pitch, PID_X, -DataORI.Gyr.X)); + short pov_y = (short)(PID_Update(Joy_roll, DataORI.Roll, PID_Y, -DataORI.Gyr.Y)); + + //throt+=pov_h; + + //float stream=DataORI.Tilt; + //if(stream>25) stream=25; + //throt*=1.0f/cosf(stream*TO_RAD); + if(throt>1000) throt=1000; + + QUAD_Set(throt, pov_x, pov_y, pov_z); //!!!!!!!!!!!!!!!! +} +//------------------------------------------------------------------------------ + + float poww=0; + bool isGoZero = false; + + +int main() +{ + //GPIO_InitPin(GPIO_PIN_13 | GPIO_PORT_C | GPIO_OUTPUT); // POWER ON 3V3 + + + CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; + DWT->CYCCNT = 0; + DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; + + //asm("BKPT 0"); + + PWM_Init(PWM_FREQ); //??? + PWM_SetAll(PWM_NONE);//??? + + LED_Init(); + + + ORI_Init(); + BAR_Init(); + + // EEP_Init(); + TIM7_Init(MAIN_UPDATE_PRIORITY); + TICK_Init(); + SBUS_Init(); + Laser_Init_v2(); + UART2_Init(57600);//LPUART1_Init + + FLOW_Init(); + //EEP_Write(0, "Hello", 6); + //char data[32]; + //EEP_Read(2, data, 32); + + TIM7_Update(MAIN_UPDATE_FREQ*2, Main_Update); + + //174 1811 + while(true) + { + // GPS_Update(); + + /* + if(SBUS_Update(Joypad, JoypadOff)) + { + poww = (Joypad.Z-174)*700/(1811-174); + PWM_SetAll(PWM_NONE); + } + */ + + + PROT_Update(); + + const unsigned long tick=TICK_GetCount(); + + static unsigned long joy_tick=tick; + + + + + //-------------------------------------------------- + + if(SBUS_Update(Joypad, JoypadOff)) + { + joy_tick=tick; + if(Joypad.SWA>JOY_MID) + { + if (!isGoZero) + { + GoZero(); + isGoZero = true; + } + Joy_pitch = (JOY_MID_PITCH - Joypad.Y)/16; + Joy_roll = (Joypad.X - JOY_MID_ROLL)/16; + Joy_yaw = (Joypad.W - JOY_MID_YAW)/16; + + if (Joypad.Z < JOY_MIN+50) Joy_throt = JOY_MIN; + else if (Joypad.Z >= JOY_MIN+50 && Joypad.Z <= JOY_MAX) + { + Joy_throt = Joypad.Z; + } + } + else + { + PWM_SetAll(PWM_NONE); + isGoZero = false; + } + } + + //-------------------------------------------------- + if((tick-joy_tick>JOY_TIMER) || JoypadOff) + { + PWM_SetAll(PWM_NONE); + } + + static unsigned long led_tick=0; + static bool led=false; + if(tick-led_tick>LED_TIMER) + { + led_tick=tick; + LED_Set(led=!led); + + } + + //short info[]={DataORI.Acc.X, DataORI.Acc.Y, DataORI.Acc.Z, DataORI.Acc.Sum, DataORI.Gyr.X, DataORI.Gyr.Y, DataORI.Gyr.Z, (short)DataORI.Pitch, (short)DataORI.Roll, (short)DataORI.Yaw}; + //TELE_Update(info, sizeof(info), TELE_TIMER); + + static int Fixed=0; + + static unsigned long log_tick=0; + if(tick-log_tick>TELE_TIMER) + { + log_tick=tick; +// +// float info[]={DataORI.Bar.Acc, DataORI.Speed.Z, DataORI.Bar.Speed}; +// UART2_Send("Z", 1); +// UART2_Send(info, sizeof(info)); +// UART2_Send("V", 1); +// +// static char buffer[128]; + //int len=sprintf(buffer, "Z:%d,%d,%d,%d,%d,%d,%d#\n", Fixed, (int)DataORI.Pitch, (int)DataORI.Roll, (int)DataORI.Yaw, (int)(DataORI.Iner.X*1000), (int)(DataORI.Iner.Y*1000), (int)(DataORI.Iner.Z*1000)); + + //if(len>0) LPUART1_Send(buffer, len); + + //int len=sprintf(buffer, "G:0,%4.3f,%4.8f,%4.8f#\n", DataGPS.Altitude, DataGPS.Coord.Latitude, DataGPS.Coord.Longitude); + + //int len=sprintf(buffer, "G:0,%d,%d\n", test_p, test_r); + + //if(len>0) LPUART1_Send(buffer, len); + + Fixed++; + } + } +} +//------------------------------------------------------------------------------ + \ No newline at end of file diff --git a/settings/Fly.Debug.cspy.bat b/settings/Fly.Debug.cspy.bat new file mode 100644 index 0000000..4a995b8 --- /dev/null +++ b/settings/Fly.Debug.cspy.bat @@ -0,0 +1,40 @@ +@REM This batch file has been generated by the IAR Embedded Workbench +@REM C-SPY Debugger, as an aid to preparing a command line for running +@REM the cspybat command line utility using the appropriate settings. +@REM +@REM Note that this file is generated every time a new debug session +@REM is initialized, so you may want to move or rename the file before +@REM making changes. +@REM +@REM You can launch cspybat by typing the name of this batch file followed +@REM by the name of the debug file (usually an ELF/DWARF or UBROF file). +@REM +@REM Read about available command line parameters in the C-SPY Debugging +@REM Guide. Hints about additional command line parameters that may be +@REM useful in specific cases: +@REM --download_only Downloads a code image without starting a debug +@REM session afterwards. +@REM --silent Omits the sign-on message. +@REM --timeout Limits the maximum allowed execution time. +@REM + + +@echo off + +if not "%~1" == "" goto debugFile + +@echo on + +"C:\iar\ewarm-9.60.3\common\bin\cspybat" -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.general.xcl" --backend -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.driver.xcl" + +@echo off +goto end + +:debugFile + +@echo on + +"C:\iar\ewarm-9.60.3\common\bin\cspybat" -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.general.xcl" "--debug_file=%~1" --backend -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.driver.xcl" + +@echo off +:end \ No newline at end of file diff --git a/settings/Fly.Debug.cspy.ps1 b/settings/Fly.Debug.cspy.ps1 new file mode 100644 index 0000000..711aecb --- /dev/null +++ b/settings/Fly.Debug.cspy.ps1 @@ -0,0 +1,31 @@ +param([String]$debugfile = ""); + +# This powershell file has been generated by the IAR Embedded Workbench +# C - SPY Debugger, as an aid to preparing a command line for running +# the cspybat command line utility using the appropriate settings. +# +# Note that this file is generated every time a new debug session +# is initialized, so you may want to move or rename the file before +# making changes. +# +# You can launch cspybat by typing Powershell.exe -File followed by the name of this batch file, followed +# by the name of the debug file (usually an ELF / DWARF or UBROF file). +# +# Read about available command line parameters in the C - SPY Debugging +# Guide. Hints about additional command line parameters that may be +# useful in specific cases : +# --download_only Downloads a code image without starting a debug +# session afterwards. +# --silent Omits the sign - on message. +# --timeout Limits the maximum allowed execution time. +# + + +if ($debugfile -eq "") +{ +& "C:\iar\ewarm-9.60.3\common\bin\cspybat" -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.general.xcl" --backend -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.driver.xcl" +} +else +{ +& "C:\iar\ewarm-9.60.3\common\bin\cspybat" -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.general.xcl" --debug_file=$debugfile --backend -f "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\settings\Fly.Debug.driver.xcl" +} diff --git a/settings/Fly.Debug.driver.xcl b/settings/Fly.Debug.driver.xcl new file mode 100644 index 0000000..9152bb8 --- /dev/null +++ b/settings/Fly.Debug.driver.xcl @@ -0,0 +1,29 @@ +--endian=little + +--cpu=Cortex-M4 + +--fpu=VFPv4_SP + +-p + +C:\iar\ewarm-9.60.3\arm\config\debugger\ST\STM32G431CB.ddf + +--drv_verify_download + +--semihosting=none + +--device=STM32G431CB + +--drv_interface=SWD + +--stlink_reset_strategy=0,0 + +--drv_swo_clock_setup=16000000,1,2000000 + +--drv_catch_exceptions=0x000 + +--drv_debug_ap=0 + + + + diff --git a/settings/Fly.Debug.general.xcl b/settings/Fly.Debug.general.xcl new file mode 100644 index 0000000..f5caf8a --- /dev/null +++ b/settings/Fly.Debug.general.xcl @@ -0,0 +1,15 @@ +C:\iar\ewarm-9.60.3\arm\bin\armPROC.dll + + C:\iar\ewarm-9.60.3\arm\bin\armSTLINK.dll + + "D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\Debug\Exe\Fly.out" + + --plugin=C:\iar\ewarm-9.60.3\arm\bin\armLibSupportUniversal.dll + + --device_macro=C:\iar\ewarm-9.60.3\arm/config/debugger/ST/STM32G4xx.dmac + + --flash_loader=C:\iar\ewarm-9.60.3\arm/config/flashloader/ST/FlashSTM32G43xxB.board + + + + diff --git a/settings/Fly.crun b/settings/Fly.crun new file mode 100644 index 0000000..d71ea55 --- /dev/null +++ b/settings/Fly.crun @@ -0,0 +1,13 @@ + + + 1 + + + * + * + * + 0 + 1 + + + diff --git a/settings/Fly.dbgdt b/settings/Fly.dbgdt new file mode 100644 index 0000000..d927bce --- /dev/null +++ b/settings/Fly.dbgdt @@ -0,0 +1,1210 @@ + + + + + 34048 + 34049 + 34050 + 34051 + 34052 + 34053 + 34054 + 34055 + 34056 + 34057 + 34058 + 34059 + 34060 + 34061 + 34062 + 34063 + 34064 + 34065 + 34066 + 34067 + 34068 + 34069 + 34070 + 34071 + 34072 + 34073 + 34074 + 34075 + 34076 + 34077 + 34078 + 34079 + 34080 + 34081 + 34082 + 34083 + 34084 + 34085 + 34086 + 34087 + 34088 + 34089 + 34090 + 34091 + 34092 + 34093 + 34094 + 34095 + 34096 + 34097 + 34098 + 34099 + 34100 + 34101 + 34102 + 34103 + 34104 + 34105 + 34106 + 34107 + 34108 + 34109 + 34110 + 34111 + 34112 + + + + + 34001 + 0 + + + + + 34390 + 34323 + 34398 + 34400 + 34397 + 34320 + 34321 + 34324 + 34322 + 0 + + + + + 37459 + 37460 + + + + + 57600 + 57601 + 57603 + 33024 + 0 + 57607 + 0 + 57635 + 57634 + 57637 + 0 + 57643 + 57644 + 0 + 33090 + 33057 + 57636 + 57640 + 57641 + 33026 + 33065 + 33063 + 33064 + 33053 + 33054 + 0 + 33035 + 33036 + 34399 + 0 + 33055 + 33056 + 0 + + + + + + Disassembly + _I0 + + + 500 + 20 + + 1 + 1 + + + + + Access + Name + Value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ataIMU + (int)(DataIMU.Bar*1000) + m + rc + Data + Uart + data + dist_mm + dx + dy + Uart.Recv.Push + Uart.Recv.Pull + tmp + buf + data + Data + pdata + VL53L0X_DEFAULT_MAX_LOOP + DeviceInfo + buf[Size] + bus + Data + result[3] + qality + Joypad + poww + dist + throt + pitch + DataORI + Joy_pitch + Joy_roll + pwm + PID_X + PID_Y + GyroShift + + + + Expression + Location + Type + Value + + + 205 + 150 + 100 + 251 + + 0 + + + 34108 + D608000099020000670B0000F0050000 + 00000000E9FFFFFF00000000E9FFFFFF + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + (int)(ay*cp - 1000*sp*cp) + (int)(1000*sp*sr*sp*sr) + az + (int)(Data.Pitch*cr*cr*cr) + (int)(Data.Roll*cp*cp*cp) + (int)(Data.Pitch*cr*cr*cr+Data.Roll*cp*cp*cp) + data + data + + + + Expression + Location + Type + Value + + + 293 + 83 + 100 + 82 + + 0 + + + 34109 + 96050000C9010000EE05000036040000 + 710400004A000000FC0500004E030000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34110 + 96050000C9010000EE05000036040000 + 710400004A000000FC0500004E030000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34111 + 96050000C9010000EE05000036040000 + 710400004A000000FC0500004E030000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34053 + 000000001700000022010000C8000000 + 04000000B7040000FC09000036050000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34085 + 000000001700000022010000C8000000 + 04000000B7040000FC09000036050000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34054 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34057 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34064 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34070 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34071 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34072 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34093 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34097 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34107 + 000000001700000022010000C8000000 + 04000000CF020000310200004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34055 + 000000001700000080020000A8000000 + 00000000000000008002000091000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34056 + A5040000FC040000AB05000065090000 + 3D020000CF020000650400004E030000 + 4096 + 0 + 0 + 32767 + 0 + + + 1 + + + + Frame + _I0 + + + 3500 + 20 + + + + 34099 + A5040000FC040000AB05000065090000 + 3D020000CF020000650400004E030000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34100 + A5040000FC040000AB05000065090000 + 3D020000CF020000650400004E030000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34058 + 00000000170000000601000078010000 + 00000000000000000601000061010000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34059 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34060 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34061 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34062 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34067 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34076 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34077 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34094 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34063 + 00000000170000000601000078010000 + FE08000030000000FC09000081040000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34079 + 00000000170000000601000078010000 + FE08000030000000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34065 + 00000000170000000601000078010000 + 4A0400003200000000060000B3020000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + 34080 + 24080000730200002A090000D4030000 + 04000000010000000400000001000000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34088 + 24080000730200002A090000D4030000 + 04000000010000000400000001000000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + 34089 + 24080000730200002A090000D4030000 + 04000000010000000400000001000000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34090 + 24080000730200002A090000D4030000 + 04000000010000000400000001000000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34091 + 24080000730200002A090000D4030000 + 04000000010000000400000001000000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34066 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34068 + FF080000FD040000210A0000AE050000 + 3D020000CF020000650400004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + + _I0 + + + 800 + + + + 34069 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34074 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34095 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34096 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34073 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34075 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34081 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34082 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34083 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34084 + 000000001700000022010000C8000000 + 0400000002040000FC09000081040000 + 4096 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34086 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34087 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34092 + 00000000170000000601000078010000 + 00000000000000000601000061010000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34098 + 000000001700000080020000A8000000 + 00000000000000008002000091000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 34101 + 00000000170000000601000078010000 + 00000000000000000601000061010000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34103 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34104 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34105 + 00000000170000000601000078010000 + 00000000000000000601000061010000 + 16384 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34106 + 0000000017000000AE010000D8000000 + 0000000000000000AE010000C1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34112 + 00000000170000000601000078010000 + 000000003200000008010000B3020000 + 4096 + 0 + 0 + 32767 + 0 + + + 1 + + + 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 + + + CMSIS-Pack + 00200000010000000100FFFF01001100434D4643546F6F6C426172427574746F6ED1840000020000001E0A0000FFFEFF00000000000000000000000000010000000100000000000000FFFEFF0A43004D005300490053002D005000610063006B0018000000 + + + 34048 + 0A0000000A0000006E0000006E000000 + 2D040000000000005B0400001A000000 + 8192 + 0 + 0 + 24 + 0 + + + 1 + + + Debug + 00200000010000000900FFFF01001100434D4643546F6F6C426172427574746F6E56860000020004003A0A0000FFFEFF00000000000000000000000000010000000100000001801386000002000400360A0000FFFEFF00000000000000000000000000010000000100000001805E860000020004003C0A0000FFFEFF000000000000000000000000000100000001000000018060860000020004003E0A0000FFFEFF00000000000000000000000000010000000100000001805D860000020004003B0A0000FFFEFF00000000000000000000000000010000000100000001801086000002000400330A0000FFFEFF00000000000000000000000000010000000100000001801186000002000000340A0000FFFEFF000000000000000000000000000100000001000000FFFF01001500434D4643546F6F6C4261724D656E75427574746F6E1486000002000400370A0000FFFEFF205200650073006500740020007400680065002000640065006200750067006700650064002000700072006F006700720061006D000A00520065007300650074000000000000000000000000000100000001000000000000000000000001000000060009802087000000000000FFFFFFFFFFFEFF06530079007300740065006D000100000000000000000000000100000001000000000000000000000001000000000009802387000000000000FFFFFFFFFFFEFF0443006F00720065000100000000000000000000000100000001000000000000000000000001000000000009802487000000000000FFFFFFFFFFFEFF0853006F006600740077006100720065000100000000000000000000000100000001000000000000000000000001000000000009802187000000000000FFFFFFFFFFFEFF12480061007200640077006100720065002000720065007300650074002000700069006E000100000000000000000000000100000001000000000000000000000001000000000009800000000000000400FFFFFFFFFFFEFF000000000000000000000000000100000001000000000000000000000001000000000009801986000000000000FFFFFFFFFFFEFF000100000000000000000000000100000001000000000000000000000001000000000001801286000002000200350A0000FFFEFF00000000000000000000000000010000000100000000000000FFFEFF0544006500620075006700DD000000 + + + 34049 + 0A0000000A0000006E0000006E000000 + 3A030000000000002D0400001A000000 + 8192 + 0 + 0 + 221 + 0 + + + 1 + + + Trace + 00200000010000000200FFFF01001100434D4643546F6F6C426172427574746F6E5392000000000400A00A0000FFFEFF03450054004D00010000000000000001000000000000000100000001805492000000000000A10A0000FFFEFF03530057004F00010000000000000001000000000000000100000000000000FFFEFF055400720061006300650023000000 + + + 34050 + 0A0000000A000000350000005A000000 + 2E040000000000007B0400001A000000 + 8192 + 0 + 1 + 35 + 0 + + + 1 + + + Main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diff --git a/settings/Fly.dnx b/settings/Fly.dnx new file mode 100644 index 0000000..2470f1c --- /dev/null +++ b/settings/Fly.dnx @@ -0,0 +1,177 @@ + + + + 1 + 10 + $PROJ_DIR$\TermIOInput.txt + 1 + 0 + 0 + 0 + + + 0 + 1 + 90 + 1 + 1 + 1 + main + 0 + 50 + + + 1 + + + 1 + 0 + 1 + 0 + 1 + + + 0 + 1 + + + 10000000 + 0 + 1 + + + 16004A002933353739303541 + + 0 + 0 + _ 0 + _ 0 + + + 0 + C:\iar\ewarm-9.60.3\arm\config\debugger\ST\STM32G431CB.ddf + + + 2271045821 + + + _ 0 + _ 0 + + + 1 + 0 + + + 0 + + + 0 + 16000000 + 1 + 2000000 + 2000000 + 8 + 0 + 0 + 1 + 15 + 0 + 0 + 0 + 0 + 0 + $PROJ_DIR$\ITM.log + + + 1 + 1 + + + 0 + + + 1 + + + altitude + 4 4 2 0 0 1 0 -100 100 + height + 0 2 1 0 1 0 0 0 4294967295 + + + {W}42:isr 4 0 + + + 0 + 0 + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + 0 + 1 + 1 + altitude + 0 4 0 + height + 0 4 1 + 0 + 1 + + + 0 + 0 + 1 + 0 + 1 + 0 + + + 0 + 0 + 1 + Ch3 + 0 0 1 + Ch2 + 0 0 1 + Ch1 + 0 0 1 + Ch0 + 0 0 1 + 0 + 1 + 0 + + + 0 + 3 + 0 + 0 + + + + _ 0 + _ "" + + + 0 + + + _ 0 "EMUL_CODE" "{$PROJ_DIR$\dev\tof.cpp}.50.9" 0 0 1 "" 0 "" 0 + _ 0 "EMUL_CODE" "{$PROJ_DIR$\dev\laser.cpp}.55.1" 0 0 1 "" 0 "" 0 + 2 + + + 0 + 0 + + diff --git a/settings/Fly.reggroups b/settings/Fly.reggroups new file mode 100644 index 0000000..5f28270 --- /dev/null +++ b/settings/Fly.reggroups @@ -0,0 +1 @@ + \ No newline at end of file diff --git a/settings/Fly.wsdt b/settings/Fly.wsdt new file mode 100644 index 0000000..b381b33 --- /dev/null +++ b/settings/Fly.wsdt @@ -0,0 +1,566 @@ + + + + + Fly/Debug + + + + + 34048 + 34049 + 34050 + 34051 + 34052 + 34053 + 34054 + 34055 + 34056 + 34057 + 34058 + 34059 + 34060 + 34061 + 34062 + 34063 + 34064 + 34065 + 34066 + + + + + 34001 + 0 + + + + + 57600 + 57601 + 57603 + 33024 + 0 + 57607 + 0 + 57635 + 57634 + 57637 + 0 + 57643 + 57644 + 0 + 33090 + 33057 + 57636 + 57640 + 57641 + 33026 + 33065 + 33063 + 33064 + 33053 + 33054 + 0 + 33035 + 33036 + 34399 + 0 + 33038 + 33039 + 0 + + + + + Fly + Fly/Output + Fly/dev + Fly/drv + Fly/utils + Fly/vl53l0x_platform + + + + + Log + _I0 + + + 1503 + 20 + + 2 + $PROJ_DIR$\DebugLog.log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ile + Line + Messages + _I0 + + + 422 + 40 + 1040 + 20 + + 2 + $WS_DIR$\BuildLog.log + 0 + 0 + + + 34052 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000EA0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34054 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000FC0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 241 + 34 + 414 + 2 + + 0 + -1 + + + 34055 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000FC0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 192 + 27 + 329 + 2 + + 0 + -1 + + + 34056 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000EA0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 34057 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000FC0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 532 + 76 + 912 + 2 + + 0 + -1 + + + 34058 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000FC0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 2 + D:\Files\Main\Projects\Fly\Fly 2/SourceBrowseLog.log + 0 + -1 + + + 34060 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000EA0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + 2 + + 0 + -1 + + + 34064 + 97FFFFFF4B03000097050000FC030000 + 04000000CB020000FC0500004E030000 + 32768 + 0 + 0 + 32767 + 0 + + + 1 + + + 34051 + 28030000FF040000A805000090050000 + 00000000B70200000006000068030000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 2 + + + + + + + + + <Right-click on a symbol in the editor to show a call graph> + + + + + + 0 + + + 0 + + + + + + 0 + + + 0 + + + File + Function + Line + + + 200 + 700 + 100 + + + + 34053 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + + Check + File + Line + Message + Severity + + + 200 + 200 + 100 + 500 + 100 + + + + 34059 + 000000001700000080020000A8000000 + 00000000000000008002000091000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + 2 + + + 0 + + + D:\Works\GIT\SKB reps\NewProc\Fly IMU\Fly IMU\Debug\BrowseInfo\Fly.pbw + + + File + Name + Scope + Symbol type + + + 300 + 300 + 300 + 300 + + + + 34061 + 00000000170000000601000078010000 + 000000003200000002010000AF020000 + 4096 + 0 + 0 + 32767 + 0 + + + 1 + + + 34062 + 000000001700000022010000C8000000 + 000000000000000022010000B1000000 + 32768 + 0 + 0 + 32767 + 0 + + + 0 + + + + Extra + Location + Type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ack + 00200000010000000100FFFF01001100434D4643546F6F6C426172427574746F6ED18400000200000008000000FFFEFF00000000000000000000000000010000000100000000000000FFFEFF0A43004D005300490053002D005000610063006B0018000000 + + + 34048 + 0A0000000A0000006E0000006E000000 + 3B03000000000000690300001A000000 + 8192 + 0 + 0 + 24 + 0 + + + 1 + + + Main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diff --git a/settings/Fly_EditorBookmarks.xml b/settings/Fly_EditorBookmarks.xml new file mode 100644 index 0000000..38c3485 --- /dev/null +++ b/settings/Fly_EditorBookmarks.xml @@ -0,0 +1,2 @@ + + diff --git a/settings/Fly_EncodingOverride.xml b/settings/Fly_EncodingOverride.xml new file mode 100644 index 0000000..dc6fd7b --- /dev/null +++ b/settings/Fly_EncodingOverride.xml @@ -0,0 +1,7 @@ + + + + C:\Users\Admin\Desktop\Fly IMU\main.cpp + UTF-8 + + diff --git a/startup_stm32g431xx.s b/startup_stm32g431xx.s new file mode 100644 index 0000000..b8d1f30 --- /dev/null +++ b/startup_stm32g431xx.s @@ -0,0 +1,585 @@ +;******************************************************************************* +;* @File Name : startup_stm32g431xx.s +;* @Author : MCD Application Team +;* @Brief : STM32G431xx Devices vector +;******************************************************************************* +;* Description : This module performs: +;* - Set the initial SP +;* - Set the initial PC == _iar_program_start, +;* - Set the vector table entries with the exceptions ISR +;* address. +;* - Branches to main in the C library (which eventually +;* calls main()). +;* After Reset the Cortex-M4 processor is in Thread mode, +;* priority is Privileged, and the Stack is set to Main. +;******************************************************************************** +;* @attention +;* +;* Copyright (c) 2019 STMicroelectronics. +;* All rights reserved. +;* +;* This software is licensed under terms that can be found in the LICENSE file +;* in the root directory of this software component. +;* If no LICENSE file comes with this software, it is provided AS-IS. +; +;******************************************************************************* +; +; 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_PVM_IRQHandler ; PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection + DCD RTC_TAMP_LSECSS_IRQHandler ; RTC, TAMP and RCC LSE_CSS through the EXTI line + DCD RTC_WKUP_IRQHandler ; RTC Wakeup through the EXTI line + DCD FLASH_IRQHandler ; FLASH + DCD RCC_IRQHandler ; RCC + DCD EXTI0_IRQHandler ; EXTI Line0 + DCD EXTI1_IRQHandler ; EXTI Line1 + DCD EXTI2_IRQHandler ; EXTI Line2 + DCD EXTI3_IRQHandler ; EXTI Line3 + DCD EXTI4_IRQHandler ; EXTI Line4 + 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 0 ; Reserved + DCD ADC1_2_IRQHandler ; ADC1 and ADC2 + DCD USB_HP_IRQHandler ; USB Device High Priority + DCD USB_LP_IRQHandler ; USB Device Low Priority + DCD FDCAN1_IT0_IRQHandler ; FDCAN1 interrupt line 0 + DCD FDCAN1_IT1_IRQHandler ; FDCAN1 interrupt line 1 + DCD EXTI9_5_IRQHandler ; External Line[9:5]s + DCD TIM1_BRK_TIM15_IRQHandler ; TIM1 Break, Transition error, Index error and TIM15 + DCD TIM1_UP_TIM16_IRQHandler ; TIM1 Update and TIM16 + DCD TIM1_TRG_COM_TIM17_IRQHandler ; TIM1 Trigger, Commutation, Direction change, Index 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 ; External Line[15:10] + DCD RTC_Alarm_IRQHandler ; RTC Alarm (A and B) through EXTI Line + DCD USBWakeUp_IRQHandler ; USB Wakeup through EXTI line + DCD TIM8_BRK_IRQHandler ; TIM8 Break, Transition error and Index error Interrupt + DCD TIM8_UP_IRQHandler ; TIM8 Update Interrupt + DCD TIM8_TRG_COM_IRQHandler ; TIM8 Trigger, Commutation, Direction change and Index Interrupt + DCD TIM8_CC_IRQHandler ; TIM8 Capture Compare Interrupt + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD LPTIM1_IRQHandler ; LP TIM1 interrupt + DCD 0 ; Reserved + DCD SPI3_IRQHandler ; SPI3 + DCD UART4_IRQHandler ; UART4 + DCD 0 ; Reserved + DCD TIM6_DAC_IRQHandler ; TIM6 and DAC1&3 underrun errors + DCD TIM7_IRQHandler ; TIM7 + DCD DMA2_Channel1_IRQHandler ; DMA2 Channel 1 + DCD DMA2_Channel2_IRQHandler ; DMA2 Channel 2 + DCD DMA2_Channel3_IRQHandler ; DMA2 Channel 3 + DCD DMA2_Channel4_IRQHandler ; DMA2 Channel 4 + DCD DMA2_Channel5_IRQHandler ; DMA2 Channel 5 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD UCPD1_IRQHandler ; UCPD1 + DCD COMP1_2_3_IRQHandler ; COMP1, COMP2 and COMP3 + DCD COMP4_IRQHandler ; COMP4 + 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 CRS_IRQHandler ; CRS Interrupt + DCD SAI1_IRQHandler ; Serial Audio Interface 1 global interrupt + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD FPU_IRQHandler ; FPU + 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 RNG_IRQHandler ; RNG global interrupt + DCD LPUART1_IRQHandler ; LP UART 1 interrupt + DCD I2C3_EV_IRQHandler ; I2C3 Event + DCD I2C3_ER_IRQHandler ; I2C3 Error + DCD DMAMUX_OVR_IRQHandler ; DMAMUX overrun global interrupt + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD DMA2_Channel6_IRQHandler ; DMA2 Channel 6 + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD CORDIC_IRQHandler ; CORDIC + DCD FMAC_IRQHandler ; FMAC + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; +;; Default interrupt handlers. +;; + THUMB + PUBWEAK Reset_Handler + SECTION .text:CODE:NOROOT:REORDER(2) +Reset_Handler + LDR R0, =SystemInit + BLX R0 + LDR R0, =__iar_program_start + BX R0 + + PUBWEAK NMI_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +NMI_Handler + B NMI_Handler + + PUBWEAK HardFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +HardFault_Handler + B HardFault_Handler + + PUBWEAK MemManage_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +MemManage_Handler + B MemManage_Handler + + PUBWEAK BusFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +BusFault_Handler + B BusFault_Handler + + PUBWEAK UsageFault_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +UsageFault_Handler + B UsageFault_Handler + + PUBWEAK SVC_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +SVC_Handler + B SVC_Handler + + PUBWEAK DebugMon_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +DebugMon_Handler + B DebugMon_Handler + + PUBWEAK PendSV_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +PendSV_Handler + B PendSV_Handler + + PUBWEAK SysTick_Handler + SECTION .text:CODE:NOROOT:REORDER(1) +SysTick_Handler + B SysTick_Handler + + PUBWEAK WWDG_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +WWDG_IRQHandler + B WWDG_IRQHandler + + PUBWEAK PVD_PVM_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +PVD_PVM_IRQHandler + B PVD_PVM_IRQHandler + + PUBWEAK RTC_TAMP_LSECSS_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RTC_TAMP_LSECSS_IRQHandler + B RTC_TAMP_LSECSS_IRQHandler + + PUBWEAK RTC_WKUP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RTC_WKUP_IRQHandler + B RTC_WKUP_IRQHandler + + PUBWEAK FLASH_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FLASH_IRQHandler + B FLASH_IRQHandler + + PUBWEAK RCC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RCC_IRQHandler + B RCC_IRQHandler + + PUBWEAK EXTI0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI0_IRQHandler + B EXTI0_IRQHandler + + PUBWEAK EXTI1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI1_IRQHandler + B EXTI1_IRQHandler + + PUBWEAK EXTI2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI2_IRQHandler + B EXTI2_IRQHandler + + PUBWEAK EXTI3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI3_IRQHandler + B EXTI3_IRQHandler + + PUBWEAK EXTI4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI4_IRQHandler + B EXTI4_IRQHandler + + PUBWEAK DMA1_Channel1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel1_IRQHandler + B DMA1_Channel1_IRQHandler + + PUBWEAK DMA1_Channel2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel2_IRQHandler + B DMA1_Channel2_IRQHandler + + PUBWEAK DMA1_Channel3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel3_IRQHandler + B DMA1_Channel3_IRQHandler + + PUBWEAK DMA1_Channel4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel4_IRQHandler + B DMA1_Channel4_IRQHandler + + PUBWEAK DMA1_Channel5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel5_IRQHandler + B DMA1_Channel5_IRQHandler + + PUBWEAK DMA1_Channel6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA1_Channel6_IRQHandler + B DMA1_Channel6_IRQHandler + + PUBWEAK ADC1_2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +ADC1_2_IRQHandler + B ADC1_2_IRQHandler + + PUBWEAK USB_HP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USB_HP_IRQHandler + B USB_HP_IRQHandler + + PUBWEAK USB_LP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USB_LP_IRQHandler + B USB_LP_IRQHandler + + PUBWEAK FDCAN1_IT0_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FDCAN1_IT0_IRQHandler + B FDCAN1_IT0_IRQHandler + + PUBWEAK FDCAN1_IT1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FDCAN1_IT1_IRQHandler + B FDCAN1_IT1_IRQHandler + + PUBWEAK EXTI9_5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI9_5_IRQHandler + B EXTI9_5_IRQHandler + + PUBWEAK TIM1_BRK_TIM15_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM1_BRK_TIM15_IRQHandler + B TIM1_BRK_TIM15_IRQHandler + + PUBWEAK TIM1_UP_TIM16_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM1_UP_TIM16_IRQHandler + B TIM1_UP_TIM16_IRQHandler + + PUBWEAK TIM1_TRG_COM_TIM17_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM1_TRG_COM_TIM17_IRQHandler + B TIM1_TRG_COM_TIM17_IRQHandler + + PUBWEAK TIM1_CC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM1_CC_IRQHandler + B TIM1_CC_IRQHandler + + PUBWEAK TIM2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM2_IRQHandler + B TIM2_IRQHandler + + PUBWEAK TIM3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM3_IRQHandler + B TIM3_IRQHandler + + PUBWEAK TIM4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM4_IRQHandler + B TIM4_IRQHandler + + PUBWEAK I2C1_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C1_EV_IRQHandler + B I2C1_EV_IRQHandler + + PUBWEAK I2C1_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C1_ER_IRQHandler + B I2C1_ER_IRQHandler + + PUBWEAK I2C2_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C2_EV_IRQHandler + B I2C2_EV_IRQHandler + + PUBWEAK I2C2_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C2_ER_IRQHandler + B I2C2_ER_IRQHandler + + PUBWEAK SPI1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI1_IRQHandler + B SPI1_IRQHandler + + PUBWEAK SPI2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI2_IRQHandler + B SPI2_IRQHandler + + PUBWEAK USART1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART1_IRQHandler + B USART1_IRQHandler + + PUBWEAK USART2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART2_IRQHandler + B USART2_IRQHandler + + PUBWEAK USART3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USART3_IRQHandler + B USART3_IRQHandler + + PUBWEAK EXTI15_10_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +EXTI15_10_IRQHandler + B EXTI15_10_IRQHandler + + PUBWEAK RTC_Alarm_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RTC_Alarm_IRQHandler + B RTC_Alarm_IRQHandler + + PUBWEAK USBWakeUp_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +USBWakeUp_IRQHandler + B USBWakeUp_IRQHandler + + PUBWEAK TIM8_BRK_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM8_BRK_IRQHandler + B TIM8_BRK_IRQHandler + + PUBWEAK TIM8_UP_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM8_UP_IRQHandler + B TIM8_UP_IRQHandler + + PUBWEAK TIM8_TRG_COM_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM8_TRG_COM_IRQHandler + B TIM8_TRG_COM_IRQHandler + + PUBWEAK TIM8_CC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM8_CC_IRQHandler + B TIM8_CC_IRQHandler + + PUBWEAK LPTIM1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +LPTIM1_IRQHandler + B LPTIM1_IRQHandler + + PUBWEAK SPI3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SPI3_IRQHandler + B SPI3_IRQHandler + + PUBWEAK UART4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UART4_IRQHandler + B UART4_IRQHandler + + PUBWEAK TIM6_DAC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM6_DAC_IRQHandler + B TIM6_DAC_IRQHandler + + PUBWEAK TIM7_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +TIM7_IRQHandler + B TIM7_IRQHandler + + PUBWEAK DMA2_Channel1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel1_IRQHandler + B DMA2_Channel1_IRQHandler + + PUBWEAK DMA2_Channel2_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel2_IRQHandler + B DMA2_Channel2_IRQHandler + + PUBWEAK DMA2_Channel3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel3_IRQHandler + B DMA2_Channel3_IRQHandler + + PUBWEAK DMA2_Channel4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel4_IRQHandler + B DMA2_Channel4_IRQHandler + + PUBWEAK DMA2_Channel5_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel5_IRQHandler + B DMA2_Channel5_IRQHandler + + PUBWEAK UCPD1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +UCPD1_IRQHandler + B UCPD1_IRQHandler + + PUBWEAK COMP1_2_3_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +COMP1_2_3_IRQHandler + B COMP1_2_3_IRQHandler + + PUBWEAK COMP4_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +COMP4_IRQHandler + B COMP4_IRQHandler + + PUBWEAK CRS_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CRS_IRQHandler + B CRS_IRQHandler + + PUBWEAK SAI1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +SAI1_IRQHandler + B SAI1_IRQHandler + + PUBWEAK FPU_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FPU_IRQHandler + B FPU_IRQHandler + + PUBWEAK RNG_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +RNG_IRQHandler + B RNG_IRQHandler + + PUBWEAK LPUART1_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +LPUART1_IRQHandler + B LPUART1_IRQHandler + + PUBWEAK I2C3_EV_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C3_EV_IRQHandler + B I2C3_EV_IRQHandler + + PUBWEAK I2C3_ER_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +I2C3_ER_IRQHandler + B I2C3_ER_IRQHandler + + PUBWEAK DMAMUX_OVR_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMAMUX_OVR_IRQHandler + B DMAMUX_OVR_IRQHandler + + PUBWEAK DMA2_Channel6_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +DMA2_Channel6_IRQHandler + B DMA2_Channel6_IRQHandler + + PUBWEAK CORDIC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +CORDIC_IRQHandler + B CORDIC_IRQHandler + + PUBWEAK FMAC_IRQHandler + SECTION .text:CODE:NOROOT:REORDER(1) +FMAC_IRQHandler + B FMAC_IRQHandler + + END diff --git a/stm32g431xx.h b/stm32g431xx.h new file mode 100644 index 0000000..4d47482 --- /dev/null +++ b/stm32g431xx.h @@ -0,0 +1,13125 @@ +/** + ****************************************************************************** + * @file stm32g431xx.h + * @author MCD Application Team + * @brief CMSIS STM32G431xx Device Peripheral Access Layer Header File. + * + * This file contains: + * - Data structures and the address mapping for all peripherals + * - Peripheral's registers declarations and bits definition + * - Macros to access peripheral's registers hardware + * + ****************************************************************************** + * @attention + * + * Copyright (c) 2019 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS_Device + * @{ + */ + +/** @addtogroup stm32g431xx + * @{ + */ + +#ifndef __STM32G431xx_H +#define __STM32G431xx_H + +#ifdef __cplusplus + extern "C" { +#endif /* __cplusplus */ + +/** @addtogroup Configuration_section_for_CMSIS + * @{ + */ + +/** + * @brief Configuration of the Cortex-M4 Processor and Core Peripherals + */ +#define __CM4_REV 0x0001U /*!< Cortex-M4 revision r0p1 */ +#define __MPU_PRESENT 1U /*!< STM32G4XX provides an MPU */ +#define __NVIC_PRIO_BITS 4U /*!< STM32G4XX uses 4 Bits for the Priority Levels */ +#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ +#define __FPU_PRESENT 1U /*!< FPU present */ + +/** + * @} + */ + +/** @addtogroup Peripheral_interrupt_number_definition + * @{ + */ + +/** + * @brief STM32G4XX Interrupt Number Definition, according to the selected device + * in @ref Library_configuration_section + */ +typedef enum +{ +/****** Cortex-M4 Processor Exceptions Numbers *********************************************************************************/ + NonMaskableInt_IRQn = -14, /*!< 2 Cortex-M4 Non Maskable Interrupt */ + HardFault_IRQn = -13, /*!< 3 Cortex-M4 Hard Fault Interrupt */ + MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ + BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ + SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ + SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ +/****** STM32 specific Interrupt Numbers ***************************************************************************************/ + WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ + PVD_PVM_IRQn = 1, /*!< PVD/PVM1/PVM2/PVM3/PVM4 through EXTI Line detection Interrupts */ + RTC_TAMP_LSECSS_IRQn = 2, /*!< RTC Tamper and TimeStamp and RCC LSE CSS interrupts through the EXTI */ + RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ + 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 */ + ADC1_2_IRQn = 18, /*!< ADC1 and ADC2 global Interrupt */ + USB_HP_IRQn = 19, /*!< USB HP Interrupt */ + USB_LP_IRQn = 20, /*!< USB LP Interrupt */ + FDCAN1_IT0_IRQn = 21, /*!< FDCAN1 IT0 Interrupt */ + FDCAN1_IT1_IRQn = 22, /*!< FDCAN1 IT1 Interrupt */ + EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ + TIM1_BRK_TIM15_IRQn = 24, /*!< TIM1 Break, Transition error, Index error and TIM15 global interrupt */ + TIM1_UP_TIM16_IRQn = 25, /*!< TIM1 Update Interrupt and TIM16 global interrupt */ + TIM1_TRG_COM_TIM17_IRQn = 26, /*!< TIM1 TIM1 Trigger, Commutation, Direction change, Index and TIM17 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 */ + RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ + USBWakeUp_IRQn = 42, /*!< USB Wakeup through EXTI line Interrupt */ + TIM8_BRK_IRQn = 43, /*!< TIM8 Break, Transition error and Index error Interrupt */ + TIM8_UP_IRQn = 44, /*!< TIM8 Update Interrupt */ + TIM8_TRG_COM_IRQn = 45, /*!< TIM8 Trigger, Commutation, Direction change and Index Interrupt */ + TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ + LPTIM1_IRQn = 49, /*!< LP TIM1 Interrupt */ + SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ + UART4_IRQn = 52, /*!< UART4 global Interrupt */ + TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&3 underrun error interrupts */ + TIM7_IRQn = 55, /*!< TIM7 global interrupts */ + 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 */ + UCPD1_IRQn = 63, /*!< UCPD global Interrupt */ + COMP1_2_3_IRQn = 64, /*!< COMP1, COMP2 and COMP3 Interrupts */ + COMP4_IRQn = 65, /*!< COMP4 */ + CRS_IRQn = 75, /*!< CRS global interrupt */ + SAI1_IRQn = 76, /*!< Serial Audio Interface global interrupt */ + FPU_IRQn = 81, /*!< FPU global interrupt */ + RNG_IRQn = 90, /*!< RNG global interrupt */ + LPUART1_IRQn = 91, /*!< LP UART 1 Interrupt */ + I2C3_EV_IRQn = 92, /*!< I2C3 Event Interrupt */ + I2C3_ER_IRQn = 93, /*!< I2C3 Error interrupt */ + DMAMUX_OVR_IRQn = 94, /*!< DMAMUX overrun global interrupt */ + DMA2_Channel6_IRQn = 97, /*!< DMA2 Channel 6 interrupt */ + CORDIC_IRQn = 100, /*!< CORDIC global Interrupt */ + FMAC_IRQn = 101 /*!< FMAC global Interrupt */ +} IRQn_Type; + +/** + * @} + */ + +#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ +#include "system_stm32g4xx.h" +#include + +/** @addtogroup Peripheral_registers_structures + * @{ + */ + +/** + * @brief Analog to Digital Converter + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< ADC interrupt and status register, Address offset: 0x00 */ + __IO uint32_t IER; /*!< ADC interrupt enable register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ + __IO uint32_t CFGR; /*!< ADC configuration register 1, Address offset: 0x0C */ + __IO uint32_t CFGR2; /*!< ADC configuration register 2, Address offset: 0x10 */ + __IO uint32_t SMPR1; /*!< ADC sampling time register 1, Address offset: 0x14 */ + __IO uint32_t SMPR2; /*!< ADC sampling time register 2, Address offset: 0x18 */ + uint32_t RESERVED1; /*!< Reserved, 0x1C */ + __IO uint32_t TR1; /*!< ADC analog watchdog 1 threshold register, Address offset: 0x20 */ + __IO uint32_t TR2; /*!< ADC analog watchdog 2 threshold register, Address offset: 0x24 */ + __IO uint32_t TR3; /*!< ADC analog watchdog 3 threshold register, Address offset: 0x28 */ + uint32_t RESERVED2; /*!< Reserved, 0x2C */ + __IO uint32_t SQR1; /*!< ADC group regular sequencer register 1, Address offset: 0x30 */ + __IO uint32_t SQR2; /*!< ADC group regular sequencer register 2, Address offset: 0x34 */ + __IO uint32_t SQR3; /*!< ADC group regular sequencer register 3, Address offset: 0x38 */ + __IO uint32_t SQR4; /*!< ADC group regular sequencer register 4, Address offset: 0x3C */ + __IO uint32_t DR; /*!< ADC group regular data register, Address offset: 0x40 */ + uint32_t RESERVED3; /*!< Reserved, 0x44 */ + uint32_t RESERVED4; /*!< Reserved, 0x48 */ + __IO uint32_t JSQR; /*!< ADC group injected sequencer register, Address offset: 0x4C */ + uint32_t RESERVED5[4]; /*!< Reserved, 0x50 - 0x5C */ + __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ + __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ + __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ + __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ + uint32_t RESERVED6[4]; /*!< Reserved, 0x70 - 0x7C */ + __IO uint32_t JDR1; /*!< ADC group injected rank 1 data register, Address offset: 0x80 */ + __IO uint32_t JDR2; /*!< ADC group injected rank 2 data register, Address offset: 0x84 */ + __IO uint32_t JDR3; /*!< ADC group injected rank 3 data register, Address offset: 0x88 */ + __IO uint32_t JDR4; /*!< ADC group injected rank 4 data register, Address offset: 0x8C */ + uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ + __IO uint32_t AWD2CR; /*!< ADC analog watchdog 2 configuration register, Address offset: 0xA0 */ + __IO uint32_t AWD3CR; /*!< ADC analog watchdog 3 Configuration Register, Address offset: 0xA4 */ + uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ + uint32_t RESERVED9; /*!< Reserved, 0x0AC */ + __IO uint32_t DIFSEL; /*!< ADC differential mode selection register, Address offset: 0xB0 */ + __IO uint32_t CALFACT; /*!< ADC calibration factors, Address offset: 0xB4 */ + uint32_t RESERVED10[2];/*!< Reserved, 0x0B8 - 0x0BC */ + __IO uint32_t GCOMP; /*!< ADC calibration factors, Address offset: 0xC0 */ +} ADC_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< ADC common status register, Address offset: 0x300 + 0x00 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x300 + 0x04 */ + __IO uint32_t CCR; /*!< ADC common configuration register, Address offset: 0x300 + 0x08 */ + __IO uint32_t CDR; /*!< ADC common group regular data register Address offset: 0x300 + 0x0C */ +} ADC_Common_TypeDef; + +/** + * @brief FD Controller Area Network + */ + +typedef struct +{ + __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ + __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ + uint32_t RESERVED1; /*!< Reserved, 0x008 */ + __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ + __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ + __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ + __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ + __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ + __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ + __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ + __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ + __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ + uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ + __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ + __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ + __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ + uint32_t RESERVED3; /*!< Reserved, 0x04C */ + __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ + __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ + __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ + __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ + uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ + __IO uint32_t RXGFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ + __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x084 */ + __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x088 */ + uint32_t RESERVED5; /*!< Reserved, 0x08C */ + __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x090 */ + __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x094 */ + __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x098 */ + __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x09C */ + uint32_t RESERVED6[8]; /*!< Reserved, 0x0A0 - 0x0BC */ + __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ + __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ + __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0C8 */ + __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0CC */ + __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D0 */ + __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D4 */ + __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0D8 */ + __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0DC */ + __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E0 */ + __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0E4 */ + __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0E8 */ +} FDCAN_GlobalTypeDef; + +/** + * @brief FD Controller Area Network Configuration + */ + +typedef struct +{ + __IO uint32_t CKDIV; /*!< FDCAN clock divider register, Address offset: 0x100 + 0x000 */ +} FDCAN_Config_TypeDef; + +/** + * @brief Comparator + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< COMP control and status register, Address offset: 0x00 */ +} COMP_TypeDef; + +/** + * @brief CRC calculation unit + */ + +typedef struct +{ + __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ + __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ + __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ + uint32_t RESERVED0; /*!< Reserved, 0x0C */ + __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ + __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ +} CRC_TypeDef; + +/** + * @brief Clock Recovery System + */ +typedef struct +{ + __IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ + __IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ + __IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ + __IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ +} CRS_TypeDef; + +/** + * @brief Digital to Analog Converter + */ + +typedef struct +{ + __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ + __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ + __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ + __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ + __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ + __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ + __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ + __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ + __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ + __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ + __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ + __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ + __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ + __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ + __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ + __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ + __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ + __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ + __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ + __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ + __IO uint32_t RESERVED[2]; + __IO uint32_t STR1; /*!< DAC Sawtooth register, Address offset: 0x58 */ + __IO uint32_t STR2; /*!< DAC Sawtooth register, Address offset: 0x5C */ + __IO uint32_t STMODR; /*!< DAC Sawtooth Mode register, Address offset: 0x60 */ +} DAC_TypeDef; + +/** + * @brief Debug MCU + */ + +typedef struct +{ + __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ + __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ + __IO uint32_t APB1FZR1; /*!< Debug MCU APB1 freeze register 1, Address offset: 0x08 */ + __IO uint32_t APB1FZR2; /*!< Debug MCU APB1 freeze register 2, Address offset: 0x0C */ + __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x10 */ +} DBGMCU_TypeDef; + +/** + * @brief DMA Controller + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA channel x configuration register */ + __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ + __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ + __IO uint32_t CMAR; /*!< DMA channel x memory address register */ +} DMA_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ + __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ +} DMA_TypeDef; + +/** + * @brief DMA Multiplexer + */ + +typedef struct +{ + __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register Address offset: 0x0004 * (channel x) */ +}DMAMUX_Channel_TypeDef; + +typedef struct +{ + __IO uint32_t CSR; /*!< DMA Channel Status Register Address offset: 0x0080 */ + __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register Address offset: 0x0084 */ +}DMAMUX_ChannelStatus_TypeDef; + +typedef struct +{ + __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register Address offset: 0x0100 + 0x0004 * (Req Gen x) */ +}DMAMUX_RequestGen_TypeDef; + +typedef struct +{ + __IO uint32_t RGSR; /*!< DMA Request Generator Status Register Address offset: 0x0140 */ + __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register Address offset: 0x0144 */ +}DMAMUX_RequestGenStatus_TypeDef; + +/** + * @brief External Interrupt/Event Controller + */ + +typedef struct +{ + __IO uint32_t IMR1; /*!< EXTI Interrupt mask register 1, Address offset: 0x00 */ + __IO uint32_t EMR1; /*!< EXTI Event mask register 1, Address offset: 0x04 */ + __IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register 1, Address offset: 0x08 */ + __IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register 1, Address offset: 0x0C */ + __IO uint32_t SWIER1; /*!< EXTI Software interrupt event register 1, Address offset: 0x10 */ + __IO uint32_t PR1; /*!< EXTI Pending register 1, Address offset: 0x14 */ + uint32_t RESERVED1; /*!< Reserved, 0x18 */ + uint32_t RESERVED2; /*!< Reserved, 0x1C */ + __IO uint32_t IMR2; /*!< EXTI Interrupt mask register 2, Address offset: 0x20 */ + __IO uint32_t EMR2; /*!< EXTI Event mask register 2, Address offset: 0x24 */ + __IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register 2, Address offset: 0x28 */ + __IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register 2, Address offset: 0x2C */ + __IO uint32_t SWIER2; /*!< EXTI Software interrupt event register 2, Address offset: 0x30 */ + __IO uint32_t PR2; /*!< EXTI Pending register 2, Address offset: 0x34 */ +} EXTI_TypeDef; + +/** + * @brief FLASH Registers + */ + +typedef struct +{ + __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ + __IO uint32_t PDKEYR; /*!< FLASH power down key register, Address offset: 0x04 */ + __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x08 */ + __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x10 */ + __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x14 */ + __IO uint32_t ECCR; /*!< FLASH ECC register, Address offset: 0x18 */ + uint32_t RESERVED1; /*!< Reserved1, Address offset: 0x1C */ + __IO uint32_t OPTR; /*!< FLASH option register, Address offset: 0x20 */ + __IO uint32_t PCROP1SR; /*!< FLASH bank1 PCROP start address register, Address offset: 0x24 */ + __IO uint32_t PCROP1ER; /*!< FLASH bank1 PCROP end address register, Address offset: 0x28 */ + __IO uint32_t WRP1AR; /*!< FLASH bank1 WRP area A address register, Address offset: 0x2C */ + __IO uint32_t WRP1BR; /*!< FLASH bank1 WRP area B address register, Address offset: 0x30 */ + uint32_t RESERVED2[15]; /*!< Reserved2, Address offset: 0x34 */ + __IO uint32_t SEC1R; /*!< FLASH Securable memory register bank1, Address offset: 0x70 */ +} FLASH_TypeDef; + +/** + * @brief FMAC + */ +typedef struct +{ + __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ + __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ + __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ + __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ + __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ + __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ +} FMAC_TypeDef; + + +/** + * @brief General Purpose I/O + */ + +typedef struct +{ + __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ + __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ + __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ + __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ + __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ + __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ + __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ + __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ + __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ + __IO uint32_t BRR; /*!< GPIO Bit Reset register, Address offset: 0x28 */ +} GPIO_TypeDef; + +/** + * @brief Inter-integrated Circuit Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ + __IO uint32_t OAR1; /*!< I2C Own address 1 register, Address offset: 0x08 */ + __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ + __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ + __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ + __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ + __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ + __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ + __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ + __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ +} I2C_TypeDef; + +/** + * @brief Independent WATCHDOG + */ + +typedef struct +{ + __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ + __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ + __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ + __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ + __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ +} IWDG_TypeDef; + +/** + * @brief LPTIMER + */ + +typedef struct +{ + __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ + __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ + __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ + __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ + __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ + __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ + __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ + __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ + __IO uint32_t OR; /*!< LPTIM Option register, Address offset: 0x20 */ +} LPTIM_TypeDef; + +/** + * @brief Operational Amplifier (OPAMP) + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ + __IO uint32_t RESERVED[5]; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ + __IO uint32_t TCMR; /*!< OPAMP timer controlled mux mode register, Address offset: 0x18 */ +} OPAMP_TypeDef; + +/** + * @brief Power Control + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x04 */ + __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x08 */ + __IO uint32_t CR4; /*!< PWR power control register 4, Address offset: 0x0C */ + __IO uint32_t SR1; /*!< PWR power status register 1, Address offset: 0x10 */ + __IO uint32_t SR2; /*!< PWR power status register 2, Address offset: 0x14 */ + __IO uint32_t SCR; /*!< PWR power status reset register, Address offset: 0x18 */ + uint32_t RESERVED; /*!< Reserved, Address offset: 0x1C */ + __IO uint32_t PUCRA; /*!< Pull_up control register of portA, Address offset: 0x20 */ + __IO uint32_t PDCRA; /*!< Pull_Down control register of portA, Address offset: 0x24 */ + __IO uint32_t PUCRB; /*!< Pull_up control register of portB, Address offset: 0x28 */ + __IO uint32_t PDCRB; /*!< Pull_Down control register of portB, Address offset: 0x2C */ + __IO uint32_t PUCRC; /*!< Pull_up control register of portC, Address offset: 0x30 */ + __IO uint32_t PDCRC; /*!< Pull_Down control register of portC, Address offset: 0x34 */ + __IO uint32_t PUCRD; /*!< Pull_up control register of portD, Address offset: 0x38 */ + __IO uint32_t PDCRD; /*!< Pull_Down control register of portD, Address offset: 0x3C */ + __IO uint32_t PUCRE; /*!< Pull_up control register of portE, Address offset: 0x40 */ + __IO uint32_t PDCRE; /*!< Pull_Down control register of portE, Address offset: 0x44 */ + __IO uint32_t PUCRF; /*!< Pull_up control register of portF, Address offset: 0x48 */ + __IO uint32_t PDCRF; /*!< Pull_Down control register of portF, Address offset: 0x4C */ + __IO uint32_t PUCRG; /*!< Pull_up control register of portG, Address offset: 0x50 */ + __IO uint32_t PDCRG; /*!< Pull_Down control register of portG, Address offset: 0x54 */ + uint32_t RESERVED1[10]; /*!< Reserved Address offset: 0x58 - 0x7C */ + __IO uint32_t CR5; /*!< PWR power control register 5, Address offset: 0x80 */ +} PWR_TypeDef; + + +/** + * @brief Reset and Clock Control + */ + +typedef struct +{ + __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ + __IO uint32_t ICSCR; /*!< RCC internal clock sources calibration register, Address offset: 0x04 */ + __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ + __IO uint32_t PLLCFGR; /*!< RCC system PLL configuration register, Address offset: 0x0C */ + uint32_t RESERVED0; /*!< Reserved, Address offset: 0x10 */ + uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ + __IO uint32_t CIER; /*!< RCC clock interrupt enable register, Address offset: 0x18 */ + __IO uint32_t CIFR; /*!< RCC clock interrupt flag register, Address offset: 0x1C */ + __IO uint32_t CICR; /*!< RCC clock interrupt clear register, Address offset: 0x20 */ + uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ + __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x28 */ + __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x2C */ + __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x30 */ + uint32_t RESERVED3; /*!< Reserved, Address offset: 0x34 */ + __IO uint32_t APB1RSTR1; /*!< RCC APB1 peripheral reset register 1, Address offset: 0x38 */ + __IO uint32_t APB1RSTR2; /*!< RCC APB1 peripheral reset register 2, Address offset: 0x3C */ + __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x40 */ + uint32_t RESERVED4; /*!< Reserved, Address offset: 0x44 */ + __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clocks enable register, Address offset: 0x48 */ + __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clocks enable register, Address offset: 0x4C */ + __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clocks enable register, Address offset: 0x50 */ + uint32_t RESERVED5; /*!< Reserved, Address offset: 0x54 */ + __IO uint32_t APB1ENR1; /*!< RCC APB1 peripheral clocks enable register 1, Address offset: 0x58 */ + __IO uint32_t APB1ENR2; /*!< RCC APB1 peripheral clocks enable register 2, Address offset: 0x5C */ + __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clocks enable register, Address offset: 0x60 */ + uint32_t RESERVED6; /*!< Reserved, Address offset: 0x64 */ + __IO uint32_t AHB1SMENR; /*!< RCC AHB1 peripheral clocks enable in sleep and stop modes register, Address offset: 0x68 */ + __IO uint32_t AHB2SMENR; /*!< RCC AHB2 peripheral clocks enable in sleep and stop modes register, Address offset: 0x6C */ + __IO uint32_t AHB3SMENR; /*!< RCC AHB3 peripheral clocks enable in sleep and stop modes register, Address offset: 0x70 */ + uint32_t RESERVED7; /*!< Reserved, Address offset: 0x74 */ + __IO uint32_t APB1SMENR1; /*!< RCC APB1 peripheral clocks enable in sleep mode and stop modes register 1, Address offset: 0x78 */ + __IO uint32_t APB1SMENR2; /*!< RCC APB1 peripheral clocks enable in sleep mode and stop modes register 2, Address offset: 0x7C */ + __IO uint32_t APB2SMENR; /*!< RCC APB2 peripheral clocks enable in sleep mode and stop modes register, Address offset: 0x80 */ + uint32_t RESERVED8; /*!< Reserved, Address offset: 0x84 */ + __IO uint32_t CCIPR; /*!< RCC peripherals independent clock configuration register, Address offset: 0x88 */ + uint32_t RESERVED9; /*!< Reserved, Address offset: 0x8C */ + __IO uint32_t BDCR; /*!< RCC backup domain control register, Address offset: 0x90 */ + __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x94 */ + __IO uint32_t CRRCR; /*!< RCC clock recovery RC register, Address offset: 0x98 */ + __IO uint32_t CCIPR2; /*!< RCC peripherals independent clock configuration register 2, Address offset: 0x9C */ +} RCC_TypeDef; + +/** + * @brief Real-Time Clock + */ +/* +* @brief Specific device feature definitions +*/ +#define RTC_TAMP_INT_6_SUPPORT +#define RTC_TAMP_INT_NB 4u + +#define RTC_TAMP_NB 3u +#define RTC_BACKUP_NB 16u + + +typedef struct +{ + __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ + __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ + __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x08 */ + __IO uint32_t ICSR; /*!< RTC initialization control and status register, Address offset: 0x0C */ + __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ + __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ + __IO uint32_t CR; /*!< RTC control register, Address offset: 0x18 */ + uint32_t RESERVED0; /*!< Reserved Address offset: 0x1C */ + uint32_t RESERVED1; /*!< Reserved Address offset: 0x20 */ + __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ + __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x28 */ + __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ + __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ + __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ + __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ + uint32_t RESERVED2; /*!< Reserved Address offset: 0x3C */ + __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x40 */ + __IO uint32_t ALRMASSR; /*!< RTC alarm A sub second register, Address offset: 0x44 */ + __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x48 */ + __IO uint32_t ALRMBSSR; /*!< RTC alarm B sub second register, Address offset: 0x4C */ + __IO uint32_t SR; /*!< RTC Status register, Address offset: 0x50 */ + __IO uint32_t MISR; /*!< RTC Masked Interrupt Status register, Address offset: 0x54 */ + uint32_t RESERVED3; /*!< Reserved Address offset: 0x58 */ + __IO uint32_t SCR; /*!< RTC Status Clear register, Address offset: 0x5C */ +} RTC_TypeDef; + +/** + * @brief Tamper and backup registers + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TAMP configuration register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TAMP configuration register 2, Address offset: 0x04 */ + uint32_t RESERVED0; /*!< no configuration register 3, Address offset: 0x08 */ + __IO uint32_t FLTCR; /*!< TAMP filter control register, Address offset: 0x0C */ + uint32_t RESERVED1[6]; /*!< Reserved Address offset: 0x10 - 0x24 */ + uint32_t RESERVED2; /*!< Reserved Address offset: 0x28 */ + __IO uint32_t IER; /*!< TAMP Interrupt enable register, Address offset: 0x2C */ + __IO uint32_t SR; /*!< TAMP Status register, Address offset: 0x30 */ + __IO uint32_t MISR; /*!< TAMP Masked Interrupt Status register Address offset: 0x34 */ + uint32_t RESERVED3; /*!< Reserved Address offset: 0x38 */ + __IO uint32_t SCR; /*!< TAMP Status clear register, Address offset: 0x3C */ + uint32_t RESERVED4[48]; /*!< Reserved Address offset: 0x040 - 0xFC */ + __IO uint32_t BKP0R; /*!< TAMP backup register 0, Address offset: 0x100 */ + __IO uint32_t BKP1R; /*!< TAMP backup register 1, Address offset: 0x104 */ + __IO uint32_t BKP2R; /*!< TAMP backup register 2, Address offset: 0x108 */ + __IO uint32_t BKP3R; /*!< TAMP backup register 3, Address offset: 0x10C */ + __IO uint32_t BKP4R; /*!< TAMP backup register 4, Address offset: 0x110 */ + __IO uint32_t BKP5R; /*!< TAMP backup register 5, Address offset: 0x114 */ + __IO uint32_t BKP6R; /*!< TAMP backup register 6, Address offset: 0x118 */ + __IO uint32_t BKP7R; /*!< TAMP backup register 7, Address offset: 0x11C */ + __IO uint32_t BKP8R; /*!< TAMP backup register 8, Address offset: 0x120 */ + __IO uint32_t BKP9R; /*!< TAMP backup register 9, Address offset: 0x124 */ + __IO uint32_t BKP10R; /*!< TAMP backup register 10, Address offset: 0x128 */ + __IO uint32_t BKP11R; /*!< TAMP backup register 11, Address offset: 0x12C */ + __IO uint32_t BKP12R; /*!< TAMP backup register 12, Address offset: 0x130 */ + __IO uint32_t BKP13R; /*!< TAMP backup register 13, Address offset: 0x134 */ + __IO uint32_t BKP14R; /*!< TAMP backup register 14, Address offset: 0x138 */ + __IO uint32_t BKP15R; /*!< TAMP backup register 15, Address offset: 0x13C */ +} TAMP_TypeDef; + +/** + * @brief Serial Audio Interface + */ + +typedef struct +{ + uint32_t RESERVED[17]; /*!< Reserved, Address offset: 0x00 to 0x40 */ + __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ + __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ +} SAI_TypeDef; + +typedef struct +{ + __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ + __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ + __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ + __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ + __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ + __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ + __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ + __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ +} SAI_Block_TypeDef; + +/** + * @brief Serial Peripheral Interface + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< SPI Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ + __IO uint32_t SR; /*!< SPI Status register, Address offset: 0x08 */ + __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ + __IO uint32_t CRCPR; /*!< SPI CRC polynomial register, Address offset: 0x10 */ + __IO uint32_t RXCRCR; /*!< SPI Rx CRC register, Address offset: 0x14 */ + __IO uint32_t TXCRCR; /*!< SPI Tx CRC register, Address offset: 0x18 */ + __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ + __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ +} SPI_TypeDef; + +/** + * @brief System configuration controller + */ + +typedef struct +{ + __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ + __IO uint32_t CFGR1; /*!< SYSCFG configuration register 1, Address offset: 0x04 */ + __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ + __IO uint32_t SCSR; /*!< SYSCFG CCMSRAM control and status register, Address offset: 0x18 */ + __IO uint32_t CFGR2; /*!< SYSCFG configuration register 2, Address offset: 0x1C */ + __IO uint32_t SWPR; /*!< SYSCFG CCMSRAM write protection register, Address offset: 0x20 */ + __IO uint32_t SKR; /*!< SYSCFG CCMSRAM Key Register, Address offset: 0x24 */ +} SYSCFG_TypeDef; + +/** + * @brief TIM + */ + +typedef struct +{ + __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ + __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ + __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ + __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ + __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ + __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ + __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ + __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ + __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ + __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ + __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ + __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ + __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ + __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ + __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ + __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ + __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ + __IO uint32_t CCR5; /*!< TIM capture/compare register 5, Address offset: 0x48 */ + __IO uint32_t CCR6; /*!< TIM capture/compare register 6, Address offset: 0x4C */ + __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x50 */ + __IO uint32_t DTR2; /*!< TIM deadtime register 2, Address offset: 0x54 */ + __IO uint32_t ECR; /*!< TIM encoder control register, Address offset: 0x58 */ + __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x5C */ + __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ + __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ + __IO uint32_t OR ; /*!< TIM option register, Address offset: 0x68 */ + uint32_t RESERVED0[220];/*!< Reserved, Address offset: 0x6C */ + __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x3DC */ + __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x3E0 */ +} TIM_TypeDef; + +/** + * @brief Universal Synchronous Asynchronous Receiver Transmitter + */ +typedef struct +{ + __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ + __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ + __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ + __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ + __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ + __IO uint32_t RTOR; /*!< USART Receiver Timeout register, Address offset: 0x14 */ + __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ + __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ + __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ + __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ + __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ + __IO uint32_t PRESC; /*!< USART Prescaler register, Address offset: 0x2C */ +} USART_TypeDef; + +/** + * @brief Universal Serial Bus Full Speed Device + */ + +typedef struct +{ + __IO uint16_t EP0R; /*!< USB Endpoint 0 register, Address offset: 0x00 */ + __IO uint16_t RESERVED0; /*!< Reserved */ + __IO uint16_t EP1R; /*!< USB Endpoint 1 register, Address offset: 0x04 */ + __IO uint16_t RESERVED1; /*!< Reserved */ + __IO uint16_t EP2R; /*!< USB Endpoint 2 register, Address offset: 0x08 */ + __IO uint16_t RESERVED2; /*!< Reserved */ + __IO uint16_t EP3R; /*!< USB Endpoint 3 register, Address offset: 0x0C */ + __IO uint16_t RESERVED3; /*!< Reserved */ + __IO uint16_t EP4R; /*!< USB Endpoint 4 register, Address offset: 0x10 */ + __IO uint16_t RESERVED4; /*!< Reserved */ + __IO uint16_t EP5R; /*!< USB Endpoint 5 register, Address offset: 0x14 */ + __IO uint16_t RESERVED5; /*!< Reserved */ + __IO uint16_t EP6R; /*!< USB Endpoint 6 register, Address offset: 0x18 */ + __IO uint16_t RESERVED6; /*!< Reserved */ + __IO uint16_t EP7R; /*!< USB Endpoint 7 register, Address offset: 0x1C */ + __IO uint16_t RESERVED7[17]; /*!< Reserved */ + __IO uint16_t CNTR; /*!< Control register, Address offset: 0x40 */ + __IO uint16_t RESERVED8; /*!< Reserved */ + __IO uint16_t ISTR; /*!< Interrupt status register, Address offset: 0x44 */ + __IO uint16_t RESERVED9; /*!< Reserved */ + __IO uint16_t FNR; /*!< Frame number register, Address offset: 0x48 */ + __IO uint16_t RESERVEDA; /*!< Reserved */ + __IO uint16_t DADDR; /*!< Device address register, Address offset: 0x4C */ + __IO uint16_t RESERVEDB; /*!< Reserved */ + __IO uint16_t BTABLE; /*!< Buffer Table address register, Address offset: 0x50 */ + __IO uint16_t RESERVEDC; /*!< Reserved */ + __IO uint16_t LPMCSR; /*!< LPM Control and Status register, Address offset: 0x54 */ + __IO uint16_t RESERVEDD; /*!< Reserved */ + __IO uint16_t BCDR; /*!< Battery Charging detector register, Address offset: 0x58 */ + __IO uint16_t RESERVEDE; /*!< Reserved */ +} USB_TypeDef; + +/** + * @brief VREFBUF + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ + __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ +} VREFBUF_TypeDef; + +/** + * @brief Window WATCHDOG + */ + +typedef struct +{ + __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ + __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ + __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ +} WWDG_TypeDef; + + +/** + * @brief RNG + */ +typedef struct +{ + __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ + __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ + __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ +} RNG_TypeDef; + +/** + * @brief CORDIC + */ + +typedef struct +{ + __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ + __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ + __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ +} CORDIC_TypeDef; + +/** + * @brief UCPD + */ + +typedef struct +{ + __IO uint32_t CFG1; /*!< UCPD configuration register 1, Address offset: 0x00 */ + __IO uint32_t CFG2; /*!< UCPD configuration register 2, Address offset: 0x04 */ + __IO uint32_t RESERVED0; /*!< UCPD reserved register, Address offset: 0x08 */ + __IO uint32_t CR; /*!< UCPD control register, Address offset: 0x0C */ + __IO uint32_t IMR; /*!< UCPD interrupt mask register, Address offset: 0x10 */ + __IO uint32_t SR; /*!< UCPD status register, Address offset: 0x14 */ + __IO uint32_t ICR; /*!< UCPD interrupt flag clear register Address offset: 0x18 */ + __IO uint32_t TX_ORDSET; /*!< UCPD Tx ordered set type register, Address offset: 0x1C */ + __IO uint32_t TX_PAYSZ; /*!< UCPD Tx payload size register, Address offset: 0x20 */ + __IO uint32_t TXDR; /*!< UCPD Tx data register, Address offset: 0x24 */ + __IO uint32_t RX_ORDSET; /*!< UCPD Rx ordered set type register, Address offset: 0x28 */ + __IO uint32_t RX_PAYSZ; /*!< UCPD Rx payload size register, Address offset: 0x2C */ + __IO uint32_t RXDR; /*!< UCPD Rx data register, Address offset: 0x30 */ + __IO uint32_t RX_ORDEXT1; /*!< UCPD Rx ordered set extension 1 register, Address offset: 0x34 */ + __IO uint32_t RX_ORDEXT2; /*!< UCPD Rx ordered set extension 2 register, Address offset: 0x38 */ +} UCPD_TypeDef; + + +/** + * @} + */ + +/** @addtogroup Peripheral_memory_map + * @{ + */ + +#define FLASH_BASE (0x08000000UL) /*!< FLASH (up to 128 kB) base address */ +#define SRAM1_BASE (0x20000000UL) /*!< SRAM1(up to 16 KB) base address */ +#define SRAM2_BASE (0x20004000UL) /*!< SRAM2(6 KB) base address */ +#define CCMSRAM_BASE (0x10000000UL) /*!< CCMSRAM(10 KB) base address */ +#define PERIPH_BASE (0x40000000UL) /*!< Peripheral base address */ + +#define SRAM1_BB_BASE (0x22000000UL) /*!< SRAM1(16 KB) base address in the bit-band region */ +#define SRAM2_BB_BASE (0x22080000UL) /*!< SRAM2(6 KB) base address in the bit-band region */ +#define CCMSRAM_BB_BASE (0x220B0000UL) /*!< CCMSRAM(10 KB) base address in the bit-band region */ +#define PERIPH_BB_BASE (0x42000000UL) /*!< Peripheral base address in the bit-band region */ +/* Legacy defines */ +#define SRAM_BASE SRAM1_BASE +#define SRAM_BB_BASE SRAM1_BB_BASE + +#define SRAM1_SIZE_MAX (0x00004000UL) /*!< maximum SRAM1 size (up to 16 KBytes) */ +#define SRAM2_SIZE (0x00001800UL) /*!< SRAM2 size (6 KBytes) */ +#define CCMSRAM_SIZE (0x00002800UL) /*!< CCMSRAM size (10 KBytes) */ + +/*!< Peripheral memory map */ +#define APB1PERIPH_BASE PERIPH_BASE +#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) +#define AHB2PERIPH_BASE (PERIPH_BASE + 0x08000000UL) + + +/*!< APB1 peripherals */ +#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) +#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) +#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) +#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) +#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) +#define CRS_BASE (APB1PERIPH_BASE + 0x2000UL) +#define TAMP_BASE (APB1PERIPH_BASE + 0x2400UL) +#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) +#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) +#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) +#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) +#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) +#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) +#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) +#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) +#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) +#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) +#define USB_BASE (APB1PERIPH_BASE + 0x5C00UL) /*!< USB_IP Peripheral Registers base address */ +#define USB_PMAADDR (APB1PERIPH_BASE + 0x6000UL) /*!< USB_IP Packet Memory Area base address */ +#define FDCAN1_BASE (APB1PERIPH_BASE + 0x6400UL) +#define FDCAN_CONFIG_BASE (APB1PERIPH_BASE + 0x6500UL) /*!< FDCAN configuration registers base address */ +#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) +#define I2C3_BASE (APB1PERIPH_BASE + 0x7800UL) +#define LPTIM1_BASE (APB1PERIPH_BASE + 0x7C00UL) +#define LPUART1_BASE (APB1PERIPH_BASE + 0x8000UL) +#define UCPD1_BASE (APB1PERIPH_BASE + 0xA000UL) +#define SRAMCAN_BASE (APB1PERIPH_BASE + 0xA400UL) + +/*!< APB2 peripherals */ +#define SYSCFG_BASE (APB2PERIPH_BASE + 0x0000UL) +#define VREFBUF_BASE (APB2PERIPH_BASE + 0x0030UL) +#define COMP1_BASE (APB2PERIPH_BASE + 0x0200UL) +#define COMP2_BASE (APB2PERIPH_BASE + 0x0204UL) +#define COMP3_BASE (APB2PERIPH_BASE + 0x0208UL) +#define COMP4_BASE (APB2PERIPH_BASE + 0x020CUL) +#define OPAMP_BASE (APB2PERIPH_BASE + 0x0300UL) +#define OPAMP1_BASE (APB2PERIPH_BASE + 0x0300UL) +#define OPAMP2_BASE (APB2PERIPH_BASE + 0x0304UL) +#define OPAMP3_BASE (APB2PERIPH_BASE + 0x0308UL) + +#define EXTI_BASE (APB2PERIPH_BASE + 0x0400UL) +#define TIM1_BASE (APB2PERIPH_BASE + 0x2C00UL) +#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) +#define TIM8_BASE (APB2PERIPH_BASE + 0x3400UL) +#define USART1_BASE (APB2PERIPH_BASE + 0x3800UL) +#define TIM15_BASE (APB2PERIPH_BASE + 0x4000UL) +#define TIM16_BASE (APB2PERIPH_BASE + 0x4400UL) +#define TIM17_BASE (APB2PERIPH_BASE + 0x4800UL) +#define SAI1_BASE (APB2PERIPH_BASE + 0x5400UL) +#define SAI1_Block_A_BASE (SAI1_BASE + 0x0004UL) +#define SAI1_Block_B_BASE (SAI1_BASE + 0x0024UL) + +/*!< AHB1 peripherals */ +#define DMA1_BASE (AHB1PERIPH_BASE) +#define DMA2_BASE (AHB1PERIPH_BASE + 0x0400UL) +#define DMAMUX1_BASE (AHB1PERIPH_BASE + 0x0800UL) +#define CORDIC_BASE (AHB1PERIPH_BASE + 0x0C00UL) +#define RCC_BASE (AHB1PERIPH_BASE + 0x1000UL) +#define FMAC_BASE (AHB1PERIPH_BASE + 0x1400UL) +#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x2000UL) +#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) + +#define DMA1_Channel1_BASE (DMA1_BASE + 0x0008UL) +#define DMA1_Channel2_BASE (DMA1_BASE + 0x001CUL) +#define DMA1_Channel3_BASE (DMA1_BASE + 0x0030UL) +#define DMA1_Channel4_BASE (DMA1_BASE + 0x0044UL) +#define DMA1_Channel5_BASE (DMA1_BASE + 0x0058UL) +#define DMA1_Channel6_BASE (DMA1_BASE + 0x006CUL) + +#define DMA2_Channel1_BASE (DMA2_BASE + 0x0008UL) +#define DMA2_Channel2_BASE (DMA2_BASE + 0x001CUL) +#define DMA2_Channel3_BASE (DMA2_BASE + 0x0030UL) +#define DMA2_Channel4_BASE (DMA2_BASE + 0x0044UL) +#define DMA2_Channel5_BASE (DMA2_BASE + 0x0058UL) +#define DMA2_Channel6_BASE (DMA2_BASE + 0x006CUL) + +#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) +#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) +#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) +#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) +#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) +#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) +#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0020UL) +#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x0024UL) +#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0028UL) +#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x002CUL) +#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0030UL) +#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x0034UL) +#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) +#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) +#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) +#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) + +#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) +#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) + +/*!< AHB2 peripherals */ +#define GPIOA_BASE (AHB2PERIPH_BASE + 0x0000UL) +#define GPIOB_BASE (AHB2PERIPH_BASE + 0x0400UL) +#define GPIOC_BASE (AHB2PERIPH_BASE + 0x0800UL) +#define GPIOD_BASE (AHB2PERIPH_BASE + 0x0C00UL) +#define GPIOE_BASE (AHB2PERIPH_BASE + 0x1000UL) +#define GPIOF_BASE (AHB2PERIPH_BASE + 0x1400UL) +#define GPIOG_BASE (AHB2PERIPH_BASE + 0x1800UL) + +#define ADC1_BASE (AHB2PERIPH_BASE + 0x08000000UL) +#define ADC2_BASE (AHB2PERIPH_BASE + 0x08000100UL) +#define ADC12_COMMON_BASE (AHB2PERIPH_BASE + 0x08000300UL) + +#define DAC_BASE (AHB2PERIPH_BASE + 0x08000800UL) +#define DAC1_BASE (AHB2PERIPH_BASE + 0x08000800UL) +#define DAC3_BASE (AHB2PERIPH_BASE + 0x08001000UL) + +#define RNG_BASE (AHB2PERIPH_BASE + 0x08060800UL) +/* Debug MCU registers base address */ +#define DBGMCU_BASE (0xE0042000UL) + +#define PACKAGE_BASE (0x1FFF7500UL) /*!< Package data register base address */ +#define UID_BASE (0x1FFF7590UL) /*!< Unique device ID register base address */ +#define FLASHSIZE_BASE (0x1FFF75E0UL) /*!< Flash size data register base address */ +/** + * @} + */ + +/** @addtogroup Peripheral_declaration + * @{ + */ +#define TIM2 ((TIM_TypeDef *) TIM2_BASE) +#define TIM3 ((TIM_TypeDef *) TIM3_BASE) +#define TIM4 ((TIM_TypeDef *) TIM4_BASE) +#define TIM6 ((TIM_TypeDef *) TIM6_BASE) +#define TIM7 ((TIM_TypeDef *) TIM7_BASE) +#define CRS ((CRS_TypeDef *) CRS_BASE) +#define TAMP ((TAMP_TypeDef *) TAMP_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 I2C1 ((I2C_TypeDef *) I2C1_BASE) +#define I2C2 ((I2C_TypeDef *) I2C2_BASE) +#define USB ((USB_TypeDef *) USB_BASE) +#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) +#define FDCAN_CONFIG ((FDCAN_Config_TypeDef *) FDCAN_CONFIG_BASE) +#define PWR ((PWR_TypeDef *) PWR_BASE) +#define I2C3 ((I2C_TypeDef *) I2C3_BASE) +#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) +#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) +#define UCPD1 ((UCPD_TypeDef *) UCPD1_BASE) + +#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) +#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) +#define COMP1 ((COMP_TypeDef *) COMP1_BASE) +#define COMP2 ((COMP_TypeDef *) COMP2_BASE) +#define COMP3 ((COMP_TypeDef *) COMP3_BASE) +#define COMP4 ((COMP_TypeDef *) COMP4_BASE) + +#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) +#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) +#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) +#define OPAMP3 ((OPAMP_TypeDef *) OPAMP3_BASE) + +#define EXTI ((EXTI_TypeDef *) EXTI_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 TIM15 ((TIM_TypeDef *) TIM15_BASE) +#define TIM16 ((TIM_TypeDef *) TIM16_BASE) +#define TIM17 ((TIM_TypeDef *) TIM17_BASE) +#define SAI1 ((SAI_TypeDef *) SAI1_BASE) +#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) +#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) +#define DMA1 ((DMA_TypeDef *) DMA1_BASE) +#define DMA2 ((DMA_TypeDef *) DMA2_BASE) +#define DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) +#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) +#define RCC ((RCC_TypeDef *) RCC_BASE) +#define FMAC ((FMAC_TypeDef *) FMAC_BASE) +#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) +#define CRC ((CRC_TypeDef *) CRC_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 ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) +#define DAC ((DAC_TypeDef *) DAC_BASE) +#define DAC1 ((DAC_TypeDef *) DAC1_BASE) +#define DAC3 ((DAC_TypeDef *) DAC3_BASE) +#define RNG ((RNG_TypeDef *) RNG_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 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 DMA2_Channel6 ((DMA_Channel_TypeDef *) DMA2_Channel6_BASE) + +#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) +#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) +#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) +#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) +#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) +#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) +#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) +#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) +#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) +#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) +#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) +#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) + +#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) +#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) +#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) +#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) + +#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) +#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) + + + +#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) + +/** + * @} + */ + +/** @addtogroup Exported_constants + * @{ + */ + + /** @addtogroup Hardware_Constant_Definition + * @{ + */ +#define LSI_STARTUP_TIME 130U /*!< LSI Maximum startup time in us */ + + /** + * @} + */ + +/** @addtogroup Peripheral_Registers_Bits_Definition + * @{ + */ + +/******************************************************************************/ +/* Peripheral Registers_Bits_Definition */ +/******************************************************************************/ + +/******************************************************************************/ +/* */ +/* Analog to Digital Converter */ +/* */ +/******************************************************************************/ + +/* + * @brief Specific device feature definitions (not present on all devices in the STM32G4 series) + */ +#define ADC_MULTIMODE_SUPPORT /*!< ADC feature available only on specific devices: multimode available on devices with several ADC instances */ + +/******************** Bit definition for ADC_ISR register *******************/ +#define ADC_ISR_ADRDY_Pos (0U) +#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ +#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC ready flag */ +#define ADC_ISR_EOSMP_Pos (1U) +#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ +#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC group regular end of sampling flag */ +#define ADC_ISR_EOC_Pos (2U) +#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ +#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC group regular end of unitary conversion flag */ +#define ADC_ISR_EOS_Pos (3U) +#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ +#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC group regular end of sequence conversions flag */ +#define ADC_ISR_OVR_Pos (4U) +#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ +#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC group regular overrun flag */ +#define ADC_ISR_JEOC_Pos (5U) +#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ +#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC group injected end of unitary conversion flag */ +#define ADC_ISR_JEOS_Pos (6U) +#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ +#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC group injected end of sequence conversions flag */ +#define ADC_ISR_AWD1_Pos (7U) +#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ +#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC analog watchdog 1 flag */ +#define ADC_ISR_AWD2_Pos (8U) +#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ +#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC analog watchdog 2 flag */ +#define ADC_ISR_AWD3_Pos (9U) +#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ +#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC analog watchdog 3 flag */ +#define ADC_ISR_JQOVF_Pos (10U) +#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ +#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC group injected contexts queue overflow flag */ + +/******************** Bit definition for ADC_IER register *******************/ +#define ADC_IER_ADRDYIE_Pos (0U) +#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ +#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC ready interrupt */ +#define ADC_IER_EOSMPIE_Pos (1U) +#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ +#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC group regular end of sampling interrupt */ +#define ADC_IER_EOCIE_Pos (2U) +#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ +#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC group regular end of unitary conversion interrupt */ +#define ADC_IER_EOSIE_Pos (3U) +#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ +#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC group regular end of sequence conversions interrupt */ +#define ADC_IER_OVRIE_Pos (4U) +#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ +#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC group regular overrun interrupt */ +#define ADC_IER_JEOCIE_Pos (5U) +#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ +#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC group injected end of unitary conversion interrupt */ +#define ADC_IER_JEOSIE_Pos (6U) +#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ +#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC group injected end of sequence conversions interrupt */ +#define ADC_IER_AWD1IE_Pos (7U) +#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ +#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC analog watchdog 1 interrupt */ +#define ADC_IER_AWD2IE_Pos (8U) +#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ +#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC analog watchdog 2 interrupt */ +#define ADC_IER_AWD3IE_Pos (9U) +#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ +#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC analog watchdog 3 interrupt */ +#define ADC_IER_JQOVFIE_Pos (10U) +#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ +#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC group injected contexts queue overflow interrupt */ + +/******************** Bit definition for ADC_CR register ********************/ +#define ADC_CR_ADEN_Pos (0U) +#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ +#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC enable */ +#define ADC_CR_ADDIS_Pos (1U) +#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ +#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC disable */ +#define ADC_CR_ADSTART_Pos (2U) +#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ +#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC group regular conversion start */ +#define ADC_CR_JADSTART_Pos (3U) +#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ +#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC group injected conversion start */ +#define ADC_CR_ADSTP_Pos (4U) +#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ +#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC group regular conversion stop */ +#define ADC_CR_JADSTP_Pos (5U) +#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ +#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC group injected conversion stop */ +#define ADC_CR_ADVREGEN_Pos (28U) +#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ +#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC voltage regulator enable */ +#define ADC_CR_DEEPPWD_Pos (29U) +#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ +#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC deep power down enable */ +#define ADC_CR_ADCALDIF_Pos (30U) +#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ +#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC differential mode for calibration */ +#define ADC_CR_ADCAL_Pos (31U) +#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ +#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC calibration */ + +/******************** Bit definition for ADC_CFGR register ******************/ +#define ADC_CFGR_DMAEN_Pos (0U) +#define ADC_CFGR_DMAEN_Msk (0x1UL << ADC_CFGR_DMAEN_Pos) /*!< 0x00000001 */ +#define ADC_CFGR_DMAEN ADC_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ +#define ADC_CFGR_DMACFG_Pos (1U) +#define ADC_CFGR_DMACFG_Msk (0x1UL << ADC_CFGR_DMACFG_Pos) /*!< 0x00000002 */ +#define ADC_CFGR_DMACFG ADC_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ + +#define ADC_CFGR_RES_Pos (3U) +#define ADC_CFGR_RES_Msk (0x3UL << ADC_CFGR_RES_Pos) /*!< 0x00000018 */ +#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC data resolution */ +#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ +#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ + +#define ADC_CFGR_EXTSEL_Pos (5U) +#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ +#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC group regular external trigger source */ +#define ADC_CFGR_EXTSEL_0 (0x1UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_CFGR_EXTSEL_1 (0x2UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ +#define ADC_CFGR_EXTSEL_2 (0x4UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ +#define ADC_CFGR_EXTSEL_3 (0x8UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ +#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ + +#define ADC_CFGR_EXTEN_Pos (10U) +#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ +#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC group regular external trigger polarity */ +#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ +#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ + +#define ADC_CFGR_OVRMOD_Pos (12U) +#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ +#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC group regular overrun configuration */ +#define ADC_CFGR_CONT_Pos (13U) +#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ +#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC group regular continuous conversion mode */ +#define ADC_CFGR_AUTDLY_Pos (14U) +#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ +#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC low power auto wait */ +#define ADC_CFGR_ALIGN_Pos (15U) +#define ADC_CFGR_ALIGN_Msk (0x1UL << ADC_CFGR_ALIGN_Pos) /*!< 0x00008000 */ +#define ADC_CFGR_ALIGN ADC_CFGR_ALIGN_Msk /*!< ADC data alignment */ +#define ADC_CFGR_DISCEN_Pos (16U) +#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ +#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC group regular sequencer discontinuous mode */ + +#define ADC_CFGR_DISCNUM_Pos (17U) +#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ +#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC group regular sequencer discontinuous number of ranks */ +#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ +#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ +#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ + +#define ADC_CFGR_JDISCEN_Pos (20U) +#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ +#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC group injected sequencer discontinuous mode */ +#define ADC_CFGR_JQM_Pos (21U) +#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ +#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC group injected contexts queue mode */ +#define ADC_CFGR_AWD1SGL_Pos (22U) +#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ +#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< ADC analog watchdog 1 monitoring a single channel or all channels */ +#define ADC_CFGR_AWD1EN_Pos (23U) +#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ +#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC analog watchdog 1 enable on scope ADC group regular */ +#define ADC_CFGR_JAWD1EN_Pos (24U) +#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ +#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC analog watchdog 1 enable on scope ADC group injected */ +#define ADC_CFGR_JAUTO_Pos (25U) +#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ +#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC group injected automatic trigger mode */ + +#define ADC_CFGR_AWD1CH_Pos (26U) +#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ +#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC analog watchdog 1 monitored channel selection */ +#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ +#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ +#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ +#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ +#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ + +#define ADC_CFGR_JQDIS_Pos (31U) +#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ +#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC group injected contexts queue disable */ + +/******************** Bit definition for ADC_CFGR2 register *****************/ +#define ADC_CFGR2_ROVSE_Pos (0U) +#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ +#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC oversampler enable on scope ADC group regular */ +#define ADC_CFGR2_JOVSE_Pos (1U) +#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ +#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC oversampler enable on scope ADC group injected */ + +#define ADC_CFGR2_OVSR_Pos (2U) +#define ADC_CFGR2_OVSR_Msk (0x7UL << ADC_CFGR2_OVSR_Pos) /*!< 0x0000001C */ +#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ +#define ADC_CFGR2_OVSR_0 (0x1UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00000004 */ +#define ADC_CFGR2_OVSR_1 (0x2UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00000008 */ +#define ADC_CFGR2_OVSR_2 (0x4UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00000010 */ + +#define ADC_CFGR2_OVSS_Pos (5U) +#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ +#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC oversampling shift */ +#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ +#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ +#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ +#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ + +#define ADC_CFGR2_TROVS_Pos (9U) +#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ +#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC oversampling discontinuous mode (triggered mode) for ADC group regular */ +#define ADC_CFGR2_ROVSM_Pos (10U) +#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ +#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC oversampling mode managing interlaced conversions of ADC group regular and group injected */ + +#define ADC_CFGR2_GCOMP_Pos (16U) +#define ADC_CFGR2_GCOMP_Msk (0x1UL << ADC_CFGR2_GCOMP_Pos) /*!< 0x00010000 */ +#define ADC_CFGR2_GCOMP ADC_CFGR2_GCOMP_Msk /*!< ADC Gain Compensation mode */ + +#define ADC_CFGR2_SWTRIG_Pos (25U) +#define ADC_CFGR2_SWTRIG_Msk (0x1UL << ADC_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ +#define ADC_CFGR2_SWTRIG ADC_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ +#define ADC_CFGR2_BULB_Pos (26U) +#define ADC_CFGR2_BULB_Msk (0x1UL << ADC_CFGR2_BULB_Pos) /*!< 0x04000000 */ +#define ADC_CFGR2_BULB ADC_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ +#define ADC_CFGR2_SMPTRIG_Pos (27U) +#define ADC_CFGR2_SMPTRIG_Msk (0x1UL << ADC_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ +#define ADC_CFGR2_SMPTRIG ADC_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ + +/******************** Bit definition for ADC_SMPR1 register *****************/ +#define ADC_SMPR1_SMP0_Pos (0U) +#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ +#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC channel 0 sampling time selection */ +#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ +#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ +#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR1_SMP1_Pos (3U) +#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ +#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC channel 1 sampling time selection */ +#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ +#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ +#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR1_SMP2_Pos (6U) +#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC channel 2 sampling time selection */ +#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ +#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ +#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR1_SMP3_Pos (9U) +#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC channel 3 sampling time selection */ +#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ +#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ +#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR1_SMP4_Pos (12U) +#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ +#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC channel 4 sampling time selection */ +#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ +#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ +#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR1_SMP5_Pos (15U) +#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ +#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC channel 5 sampling time selection */ +#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ +#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ +#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR1_SMP6_Pos (18U) +#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC channel 6 sampling time selection */ +#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ +#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ +#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR1_SMP7_Pos (21U) +#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC channel 7 sampling time selection */ +#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ +#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ +#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR1_SMP8_Pos (24U) +#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ +#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC channel 8 sampling time selection */ +#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ +#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ +#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ + +#define ADC_SMPR1_SMP9_Pos (27U) +#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ +#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC channel 9 sampling time selection */ +#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ +#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ +#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ + +#define ADC_SMPR1_SMPPLUS_Pos (31U) +#define ADC_SMPR1_SMPPLUS_Msk (0x1UL << ADC_SMPR1_SMPPLUS_Pos) /*!< 0x80000000 */ +#define ADC_SMPR1_SMPPLUS ADC_SMPR1_SMPPLUS_Msk /*!< ADC channels sampling time additional setting */ + +/******************** Bit definition for ADC_SMPR2 register *****************/ +#define ADC_SMPR2_SMP10_Pos (0U) +#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ +#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC channel 10 sampling time selection */ +#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ +#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ +#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ + +#define ADC_SMPR2_SMP11_Pos (3U) +#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ +#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC channel 11 sampling time selection */ +#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ +#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ +#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ + +#define ADC_SMPR2_SMP12_Pos (6U) +#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ +#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC channel 12 sampling time selection */ +#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ +#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ +#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ + +#define ADC_SMPR2_SMP13_Pos (9U) +#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ +#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC channel 13 sampling time selection */ +#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ +#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ +#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ + +#define ADC_SMPR2_SMP14_Pos (12U) +#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ +#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC channel 14 sampling time selection */ +#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ +#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ +#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ + +#define ADC_SMPR2_SMP15_Pos (15U) +#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ +#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC channel 15 sampling time selection */ +#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ +#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ +#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ + +#define ADC_SMPR2_SMP16_Pos (18U) +#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ +#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC channel 16 sampling time selection */ +#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ +#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ +#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ + +#define ADC_SMPR2_SMP17_Pos (21U) +#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ +#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC channel 17 sampling time selection */ +#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ +#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ +#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ + +#define ADC_SMPR2_SMP18_Pos (24U) +#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ +#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC channel 18 sampling time selection */ +#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ +#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ +#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ + +/******************** Bit definition for ADC_TR1 register *******************/ +#define ADC_TR1_LT1_Pos (0U) +#define ADC_TR1_LT1_Msk (0xFFFUL << ADC_TR1_LT1_Pos) /*!< 0x00000FFF */ +#define ADC_TR1_LT1 ADC_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ + +#define ADC_TR1_AWDFILT_Pos (12U) +#define ADC_TR1_AWDFILT_Msk (0x7UL << ADC_TR1_AWDFILT_Pos) /*!< 0x00007000 */ +#define ADC_TR1_AWDFILT ADC_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ +#define ADC_TR1_AWDFILT_0 (0x1UL << ADC_TR1_AWDFILT_Pos) /*!< 0x00001000 */ +#define ADC_TR1_AWDFILT_1 (0x2UL << ADC_TR1_AWDFILT_Pos) /*!< 0x00002000 */ +#define ADC_TR1_AWDFILT_2 (0x4UL << ADC_TR1_AWDFILT_Pos) /*!< 0x00004000 */ + +#define ADC_TR1_HT1_Pos (16U) +#define ADC_TR1_HT1_Msk (0xFFFUL << ADC_TR1_HT1_Pos) /*!< 0x0FFF0000 */ +#define ADC_TR1_HT1 ADC_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ + +/******************** Bit definition for ADC_TR2 register *******************/ +#define ADC_TR2_LT2_Pos (0U) +#define ADC_TR2_LT2_Msk (0xFFUL << ADC_TR2_LT2_Pos) /*!< 0x000000FF */ +#define ADC_TR2_LT2 ADC_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ + +#define ADC_TR2_HT2_Pos (16U) +#define ADC_TR2_HT2_Msk (0xFFUL << ADC_TR2_HT2_Pos) /*!< 0x00FF0000 */ +#define ADC_TR2_HT2 ADC_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ + +/******************** Bit definition for ADC_TR3 register *******************/ +#define ADC_TR3_LT3_Pos (0U) +#define ADC_TR3_LT3_Msk (0xFFUL << ADC_TR3_LT3_Pos) /*!< 0x000000FF */ +#define ADC_TR3_LT3 ADC_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ + +#define ADC_TR3_HT3_Pos (16U) +#define ADC_TR3_HT3_Msk (0xFFUL << ADC_TR3_HT3_Pos) /*!< 0x00FF0000 */ +#define ADC_TR3_HT3 ADC_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ + +/******************** Bit definition for ADC_SQR1 register ******************/ +#define ADC_SQR1_L_Pos (0U) +#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ +#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC group regular sequencer scan length */ +#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ +#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ +#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ +#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ + +#define ADC_SQR1_SQ1_Pos (6U) +#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ +#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC group regular sequencer rank 1 */ +#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ +#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ +#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ +#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ +#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ + +#define ADC_SQR1_SQ2_Pos (12U) +#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ +#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC group regular sequencer rank 2 */ +#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ +#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ +#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ +#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ +#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ + +#define ADC_SQR1_SQ3_Pos (18U) +#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ +#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC group regular sequencer rank 3 */ +#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ +#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ +#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ +#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ +#define ADC_SQR1_SQ3_4 (0x10UL<< ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ + +#define ADC_SQR1_SQ4_Pos (24U) +#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ +#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC group regular sequencer rank 4 */ +#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ +#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ +#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ +#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ +#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR2 register ******************/ +#define ADC_SQR2_SQ5_Pos (0U) +#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ +#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC group regular sequencer rank 5 */ +#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ +#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ +#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ +#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ +#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ + +#define ADC_SQR2_SQ6_Pos (6U) +#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ +#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC group regular sequencer rank 6 */ +#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ +#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ +#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ +#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ +#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ + +#define ADC_SQR2_SQ7_Pos (12U) +#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ +#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC group regular sequencer rank 7 */ +#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ +#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ +#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ +#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ +#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ + +#define ADC_SQR2_SQ8_Pos (18U) +#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ +#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC group regular sequencer rank 8 */ +#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ +#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ +#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ +#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ +#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ + +#define ADC_SQR2_SQ9_Pos (24U) +#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ +#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC group regular sequencer rank 9 */ +#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ +#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ +#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ +#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ +#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR3 register ******************/ +#define ADC_SQR3_SQ10_Pos (0U) +#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ +#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC group regular sequencer rank 10 */ +#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ +#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ +#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ +#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ +#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ + +#define ADC_SQR3_SQ11_Pos (6U) +#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ +#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC group regular sequencer rank 11 */ +#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ +#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ +#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ +#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ +#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ + +#define ADC_SQR3_SQ12_Pos (12U) +#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ +#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC group regular sequencer rank 12 */ +#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ +#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ +#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ +#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ +#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ + +#define ADC_SQR3_SQ13_Pos (18U) +#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ +#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC group regular sequencer rank 13 */ +#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ +#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ +#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ +#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ +#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ + +#define ADC_SQR3_SQ14_Pos (24U) +#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ +#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC group regular sequencer rank 14 */ +#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ +#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ +#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ +#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ +#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ + +/******************** Bit definition for ADC_SQR4 register ******************/ +#define ADC_SQR4_SQ15_Pos (0U) +#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ +#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC group regular sequencer rank 15 */ +#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ +#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ +#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ +#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ +#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ + +#define ADC_SQR4_SQ16_Pos (6U) +#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ +#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC group regular sequencer rank 16 */ +#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ +#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ +#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ +#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ +#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ + +/******************** Bit definition for ADC_DR register ********************/ +#define ADC_DR_RDATA_Pos (0U) +#define ADC_DR_RDATA_Msk (0xFFFFUL << ADC_DR_RDATA_Pos) /*!< 0x0000FFFF */ +#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC group regular conversion data */ + +/******************** Bit definition for ADC_JSQR register ******************/ +#define ADC_JSQR_JL_Pos (0U) +#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ +#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC group injected sequencer scan length */ +#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ +#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ + +#define ADC_JSQR_JEXTSEL_Pos (2U) +#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ +#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC group injected external trigger source */ +#define ADC_JSQR_JEXTSEL_0 (0x1UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ +#define ADC_JSQR_JEXTSEL_1 (0x2UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ +#define ADC_JSQR_JEXTSEL_2 (0x4UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ +#define ADC_JSQR_JEXTSEL_3 (0x8UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ +#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ + +#define ADC_JSQR_JEXTEN_Pos (7U) +#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ +#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC group injected external trigger polarity */ +#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ +#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ + +#define ADC_JSQR_JSQ1_Pos (9U) +#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ +#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC group injected sequencer rank 1 */ +#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ +#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ +#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ +#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ +#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ + +#define ADC_JSQR_JSQ2_Pos (15U) +#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x0007C000 */ +#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC group injected sequencer rank 2 */ +#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00004000 */ +#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ +#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ +#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ +#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ + +#define ADC_JSQR_JSQ3_Pos (21U) +#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ +#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC group injected sequencer rank 3 */ +#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ +#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ +#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ +#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ +#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ + +#define ADC_JSQR_JSQ4_Pos (27U) +#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ +#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC group injected sequencer rank 4 */ +#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ +#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ +#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ +#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ +#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ + +/******************** Bit definition for ADC_OFR1 register ******************/ +#define ADC_OFR1_OFFSET1_Pos (0U) +#define ADC_OFR1_OFFSET1_Msk (0xFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ +#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC offset number 1 offset level */ + +#define ADC_OFR1_OFFSETPOS_Pos (24U) +#define ADC_OFR1_OFFSETPOS_Msk (0x1UL << ADC_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC_OFR1_OFFSETPOS ADC_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ +#define ADC_OFR1_SATEN_Pos (25U) +#define ADC_OFR1_SATEN_Msk (0x1UL << ADC_OFR1_SATEN_Pos) /*!< 0x02000000 */ +#define ADC_OFR1_SATEN ADC_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ + +#define ADC_OFR1_OFFSET1_CH_Pos (26U) +#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC offset number 1 channel selection */ +#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR1_OFFSET1_EN_Pos (31U) +#define ADC_OFR1_OFFSET1_EN_Msk (0x1UL << ADC_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ +#define ADC_OFR1_OFFSET1_EN ADC_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ + +/******************** Bit definition for ADC_OFR2 register ******************/ +#define ADC_OFR2_OFFSET2_Pos (0U) +#define ADC_OFR2_OFFSET2_Msk (0xFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ +#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC offset number 2 offset level */ + +#define ADC_OFR2_OFFSETPOS_Pos (24U) +#define ADC_OFR2_OFFSETPOS_Msk (0x1UL << ADC_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC_OFR2_OFFSETPOS ADC_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ +#define ADC_OFR2_SATEN_Pos (25U) +#define ADC_OFR2_SATEN_Msk (0x1UL << ADC_OFR2_SATEN_Pos) /*!< 0x02000000 */ +#define ADC_OFR2_SATEN ADC_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ + +#define ADC_OFR2_OFFSET2_CH_Pos (26U) +#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC offset number 2 channel selection */ +#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR2_OFFSET2_EN_Pos (31U) +#define ADC_OFR2_OFFSET2_EN_Msk (0x1UL << ADC_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ +#define ADC_OFR2_OFFSET2_EN ADC_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ + +/******************** Bit definition for ADC_OFR3 register ******************/ +#define ADC_OFR3_OFFSET3_Pos (0U) +#define ADC_OFR3_OFFSET3_Msk (0xFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ +#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC offset number 3 offset level */ + +#define ADC_OFR3_OFFSETPOS_Pos (24U) +#define ADC_OFR3_OFFSETPOS_Msk (0x1UL << ADC_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC_OFR3_OFFSETPOS ADC_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ +#define ADC_OFR3_SATEN_Pos (25U) +#define ADC_OFR3_SATEN_Msk (0x1UL << ADC_OFR3_SATEN_Pos) /*!< 0x02000000 */ +#define ADC_OFR3_SATEN ADC_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ + +#define ADC_OFR3_OFFSET3_CH_Pos (26U) +#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC offset number 3 channel selection */ +#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR3_OFFSET3_EN_Pos (31U) +#define ADC_OFR3_OFFSET3_EN_Msk (0x1UL << ADC_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ +#define ADC_OFR3_OFFSET3_EN ADC_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ + +/******************** Bit definition for ADC_OFR4 register ******************/ +#define ADC_OFR4_OFFSET4_Pos (0U) +#define ADC_OFR4_OFFSET4_Msk (0xFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ +#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC offset number 4 offset level */ + +#define ADC_OFR4_OFFSETPOS_Pos (24U) +#define ADC_OFR4_OFFSETPOS_Msk (0x1UL << ADC_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ +#define ADC_OFR4_OFFSETPOS ADC_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ +#define ADC_OFR4_SATEN_Pos (25U) +#define ADC_OFR4_SATEN_Msk (0x1UL << ADC_OFR4_SATEN_Pos) /*!< 0x02000000 */ +#define ADC_OFR4_SATEN ADC_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ + +#define ADC_OFR4_OFFSET4_CH_Pos (26U) +#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ +#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC offset number 4 channel selection */ +#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ +#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ +#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ +#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ +#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ + +#define ADC_OFR4_OFFSET4_EN_Pos (31U) +#define ADC_OFR4_OFFSET4_EN_Msk (0x1UL << ADC_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ +#define ADC_OFR4_OFFSET4_EN ADC_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ + +/******************** Bit definition for ADC_JDR1 register ******************/ +#define ADC_JDR1_JDATA_Pos (0U) +#define ADC_JDR1_JDATA_Msk (0xFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0x0000FFFF */ +#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC group injected sequencer rank 1 conversion data */ + +/******************** Bit definition for ADC_JDR2 register ******************/ +#define ADC_JDR2_JDATA_Pos (0U) +#define ADC_JDR2_JDATA_Msk (0xFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0x0000FFFF */ +#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC group injected sequencer rank 2 conversion data */ + +/******************** Bit definition for ADC_JDR3 register ******************/ +#define ADC_JDR3_JDATA_Pos (0U) +#define ADC_JDR3_JDATA_Msk (0xFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0x0000FFFF */ +#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC group injected sequencer rank 3 conversion data */ + +/******************** Bit definition for ADC_JDR4 register ******************/ +#define ADC_JDR4_JDATA_Pos (0U) +#define ADC_JDR4_JDATA_Msk (0xFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0x0000FFFF */ +#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC group injected sequencer rank 4 conversion data */ + +/******************** Bit definition for ADC_AWD2CR register ****************/ +#define ADC_AWD2CR_AWD2CH_Pos (0U) +#define ADC_AWD2CR_AWD2CH_Msk (0x7FFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x0007FFFF */ +#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC analog watchdog 2 monitored channel selection */ +#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ + +/******************** Bit definition for ADC_AWD3CR register ****************/ +#define ADC_AWD3CR_AWD3CH_Pos (0U) +#define ADC_AWD3CR_AWD3CH_Msk (0x7FFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x0007FFFF */ +#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC analog watchdog 3 monitored channel selection */ +#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ +#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ +#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ +#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ +#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ +#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ +#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ +#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ +#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ +#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ +#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ +#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ +#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ +#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ +#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ +#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ +#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ +#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ +#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ + +/******************** Bit definition for ADC_DIFSEL register ****************/ +#define ADC_DIFSEL_DIFSEL_Pos (0U) +#define ADC_DIFSEL_DIFSEL_Msk (0x7FFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x0007FFFF */ +#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC channel differential or single-ended mode */ +#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ +#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ +#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ +#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ +#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ +#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ +#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ +#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ +#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ +#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ +#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ +#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ +#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ +#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ +#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ +#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ +#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ +#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ +#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ + +/******************** Bit definition for ADC_CALFACT register ***************/ +#define ADC_CALFACT_CALFACT_S_Pos (0U) +#define ADC_CALFACT_CALFACT_S_Msk (0x7FUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x0000007F */ +#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factor in single-ended mode */ +#define ADC_CALFACT_CALFACT_S_0 (0x01UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ +#define ADC_CALFACT_CALFACT_S_1 (0x02UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ +#define ADC_CALFACT_CALFACT_S_2 (0x04UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ +#define ADC_CALFACT_CALFACT_S_3 (0x08UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ +#define ADC_CALFACT_CALFACT_S_4 (0x10UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ +#define ADC_CALFACT_CALFACT_S_5 (0x20UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ +#define ADC_CALFACT_CALFACT_S_6 (0x40UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000030 */ + +#define ADC_CALFACT_CALFACT_D_Pos (16U) +#define ADC_CALFACT_CALFACT_D_Msk (0x7FUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x007F0000 */ +#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factor in differential mode */ +#define ADC_CALFACT_CALFACT_D_0 (0x01UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ +#define ADC_CALFACT_CALFACT_D_1 (0x02UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ +#define ADC_CALFACT_CALFACT_D_2 (0x04UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ +#define ADC_CALFACT_CALFACT_D_3 (0x08UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ +#define ADC_CALFACT_CALFACT_D_4 (0x10UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ +#define ADC_CALFACT_CALFACT_D_5 (0x20UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ +#define ADC_CALFACT_CALFACT_D_6 (0x40UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00300000 */ + +/******************** Bit definition for ADC_GCOMP register *****************/ +#define ADC_GCOMP_GCOMPCOEFF_Pos (0U) +#define ADC_GCOMP_GCOMPCOEFF_Msk (0x3FFFUL << ADC_GCOMP_GCOMPCOEFF_Pos) /*!< 0x00003FFF */ +#define ADC_GCOMP_GCOMPCOEFF ADC_GCOMP_GCOMPCOEFF_Msk /*!< ADC Gain Compensation Coefficient */ + +/************************* ADC Common registers *****************************/ +/******************** Bit definition for ADC_CSR register *******************/ +#define ADC_CSR_ADRDY_MST_Pos (0U) +#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ +#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< ADC multimode master ready flag */ +#define ADC_CSR_EOSMP_MST_Pos (1U) +#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ +#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< ADC multimode master group regular end of sampling flag */ +#define ADC_CSR_EOC_MST_Pos (2U) +#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ +#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< ADC multimode master group regular end of unitary conversion flag */ +#define ADC_CSR_EOS_MST_Pos (3U) +#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ +#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< ADC multimode master group regular end of sequence conversions flag */ +#define ADC_CSR_OVR_MST_Pos (4U) +#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ +#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< ADC multimode master group regular overrun flag */ +#define ADC_CSR_JEOC_MST_Pos (5U) +#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ +#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< ADC multimode master group injected end of unitary conversion flag */ +#define ADC_CSR_JEOS_MST_Pos (6U) +#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ +#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< ADC multimode master group injected end of sequence conversions flag */ +#define ADC_CSR_AWD1_MST_Pos (7U) +#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ +#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< ADC multimode master analog watchdog 1 flag */ +#define ADC_CSR_AWD2_MST_Pos (8U) +#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ +#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< ADC multimode master analog watchdog 2 flag */ +#define ADC_CSR_AWD3_MST_Pos (9U) +#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ +#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< ADC multimode master analog watchdog 3 flag */ +#define ADC_CSR_JQOVF_MST_Pos (10U) +#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ +#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< ADC multimode master group injected contexts queue overflow flag */ + +#define ADC_CSR_ADRDY_SLV_Pos (16U) +#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ +#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< ADC multimode slave ready flag */ +#define ADC_CSR_EOSMP_SLV_Pos (17U) +#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ +#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< ADC multimode slave group regular end of sampling flag */ +#define ADC_CSR_EOC_SLV_Pos (18U) +#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ +#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< ADC multimode slave group regular end of unitary conversion flag */ +#define ADC_CSR_EOS_SLV_Pos (19U) +#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ +#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< ADC multimode slave group regular end of sequence conversions flag */ +#define ADC_CSR_OVR_SLV_Pos (20U) +#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ +#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< ADC multimode slave group regular overrun flag */ +#define ADC_CSR_JEOC_SLV_Pos (21U) +#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ +#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< ADC multimode slave group injected end of unitary conversion flag */ +#define ADC_CSR_JEOS_SLV_Pos (22U) +#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ +#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< ADC multimode slave group injected end of sequence conversions flag */ +#define ADC_CSR_AWD1_SLV_Pos (23U) +#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ +#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< ADC multimode slave analog watchdog 1 flag */ +#define ADC_CSR_AWD2_SLV_Pos (24U) +#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ +#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< ADC multimode slave analog watchdog 2 flag */ +#define ADC_CSR_AWD3_SLV_Pos (25U) +#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ +#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< ADC multimode slave analog watchdog 3 flag */ +#define ADC_CSR_JQOVF_SLV_Pos (26U) +#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ +#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< ADC multimode slave group injected contexts queue overflow flag */ + +/******************** Bit definition for ADC_CCR register *******************/ +#define ADC_CCR_DUAL_Pos (0U) +#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ +#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< ADC multimode mode selection */ +#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ +#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ +#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ +#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ +#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ + +#define ADC_CCR_DELAY_Pos (8U) +#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ +#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< ADC multimode delay between 2 sampling phases */ +#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ +#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ +#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ +#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ + +#define ADC_CCR_DMACFG_Pos (13U) +#define ADC_CCR_DMACFG_Msk (0x1UL << ADC_CCR_DMACFG_Pos) /*!< 0x00002000 */ +#define ADC_CCR_DMACFG ADC_CCR_DMACFG_Msk /*!< ADC multimode DMA transfer configuration */ + +#define ADC_CCR_MDMA_Pos (14U) +#define ADC_CCR_MDMA_Msk (0x3UL << ADC_CCR_MDMA_Pos) /*!< 0x0000C000 */ +#define ADC_CCR_MDMA ADC_CCR_MDMA_Msk /*!< ADC multimode DMA transfer enable */ +#define ADC_CCR_MDMA_0 (0x1UL << ADC_CCR_MDMA_Pos) /*!< 0x00004000 */ +#define ADC_CCR_MDMA_1 (0x2UL << ADC_CCR_MDMA_Pos) /*!< 0x00008000 */ + +#define ADC_CCR_CKMODE_Pos (16U) +#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ +#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC common clock source and prescaler (prescaler only for clock source synchronous) */ +#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ +#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ + +#define ADC_CCR_PRESC_Pos (18U) +#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ +#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC common clock prescaler, only for clock source asynchronous */ +#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ +#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ +#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ +#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ + +#define ADC_CCR_VREFEN_Pos (22U) +#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ +#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< ADC internal path to VrefInt enable */ +#define ADC_CCR_VSENSESEL_Pos (23U) +#define ADC_CCR_VSENSESEL_Msk (0x1UL << ADC_CCR_VSENSESEL_Pos) /*!< 0x00800000 */ +#define ADC_CCR_VSENSESEL ADC_CCR_VSENSESEL_Msk /*!< ADC internal path to temperature sensor enable */ +#define ADC_CCR_VBATSEL_Pos (24U) +#define ADC_CCR_VBATSEL_Msk (0x1UL << ADC_CCR_VBATSEL_Pos) /*!< 0x01000000 */ +#define ADC_CCR_VBATSEL ADC_CCR_VBATSEL_Msk /*!< ADC internal path to battery voltage enable */ + +/******************** Bit definition for ADC_CDR register *******************/ +#define ADC_CDR_RDATA_MST_Pos (0U) +#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ +#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ + +#define ADC_CDR_RDATA_SLV_Pos (16U) +#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ +#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ + + +/******************************************************************************/ +/* */ +/* Analog Comparators (COMP) */ +/* */ +/******************************************************************************/ +/********************** Bit definition for COMP_CSR register ****************/ +#define COMP_CSR_EN_Pos (0U) +#define COMP_CSR_EN_Msk (0x1UL << COMP_CSR_EN_Pos) /*!< 0x00000001 */ +#define COMP_CSR_EN COMP_CSR_EN_Msk /*!< Comparator enable */ + +#define COMP_CSR_INMSEL_Pos (4U) +#define COMP_CSR_INMSEL_Msk (0xFUL << COMP_CSR_INMSEL_Pos) /*!< 0x00000070 */ +#define COMP_CSR_INMSEL COMP_CSR_INMSEL_Msk /*!< Comparator input minus selection */ +#define COMP_CSR_INMSEL_0 (0x1UL << COMP_CSR_INMSEL_Pos) /*!< 0x00000010 */ +#define COMP_CSR_INMSEL_1 (0x2UL << COMP_CSR_INMSEL_Pos) /*!< 0x00000020 */ +#define COMP_CSR_INMSEL_2 (0x4UL << COMP_CSR_INMSEL_Pos) /*!< 0x00000040 */ +#define COMP_CSR_INMSEL_3 (0x8UL << COMP_CSR_INMSEL_Pos) /*!< 0x00000080 */ + +#define COMP_CSR_INPSEL_Pos (8U) +#define COMP_CSR_INPSEL_Msk (0x1UL << COMP_CSR_INPSEL_Pos) /*!< 0x00000100 */ +#define COMP_CSR_INPSEL COMP_CSR_INPSEL_Msk /*!< Comparator input plus selection */ + +#define COMP_CSR_POLARITY_Pos (15U) +#define COMP_CSR_POLARITY_Msk (0x1UL << COMP_CSR_POLARITY_Pos) /*!< 0x00008000 */ +#define COMP_CSR_POLARITY COMP_CSR_POLARITY_Msk /*!< Comparator output polarity */ + +#define COMP_CSR_HYST_Pos (16U) +#define COMP_CSR_HYST_Msk (0x7UL << COMP_CSR_HYST_Pos) /*!< 0x00070000 */ +#define COMP_CSR_HYST COMP_CSR_HYST_Msk /*!< Comparator hysteresis */ +#define COMP_CSR_HYST_0 (0x1UL << COMP_CSR_HYST_Pos) /*!< 0x00010000 */ +#define COMP_CSR_HYST_1 (0x2UL << COMP_CSR_HYST_Pos) /*!< 0x00020000 */ +#define COMP_CSR_HYST_2 (0x4UL << COMP_CSR_HYST_Pos) /*!< 0x00040000 */ + +#define COMP_CSR_BLANKING_Pos (19U) +#define COMP_CSR_BLANKING_Msk (0x7UL << COMP_CSR_BLANKING_Pos) /*!< 0x00380000 */ +#define COMP_CSR_BLANKING COMP_CSR_BLANKING_Msk /*!< Comparator blanking source */ +#define COMP_CSR_BLANKING_0 (0x1UL << COMP_CSR_BLANKING_Pos) /*!< 0x00080000 */ +#define COMP_CSR_BLANKING_1 (0x2UL << COMP_CSR_BLANKING_Pos) /*!< 0x00100000 */ +#define COMP_CSR_BLANKING_2 (0x4UL << COMP_CSR_BLANKING_Pos) /*!< 0x00200000 */ + +#define COMP_CSR_BRGEN_Pos (22U) +#define COMP_CSR_BRGEN_Msk (0x1UL << COMP_CSR_BRGEN_Pos) /*!< 0x00400000 */ +#define COMP_CSR_BRGEN COMP_CSR_BRGEN_Msk /*!< Comparator scaler bridge enable */ + +#define COMP_CSR_SCALEN_Pos (23U) +#define COMP_CSR_SCALEN_Msk (0x1UL << COMP_CSR_SCALEN_Pos) /*!< 0x00800000 */ +#define COMP_CSR_SCALEN COMP_CSR_SCALEN_Msk /*!< Comparator voltage scaler enable */ + +#define COMP_CSR_VALUE_Pos (30U) +#define COMP_CSR_VALUE_Msk (0x1UL << COMP_CSR_VALUE_Pos) /*!< 0x40000000 */ +#define COMP_CSR_VALUE COMP_CSR_VALUE_Msk /*!< Comparator output level */ + +#define COMP_CSR_LOCK_Pos (31U) +#define COMP_CSR_LOCK_Msk (0x1UL << COMP_CSR_LOCK_Pos) /*!< 0x80000000 */ +#define COMP_CSR_LOCK COMP_CSR_LOCK_Msk /*!< Comparator lock */ + +/******************************************************************************/ +/* */ +/* CORDIC calculation unit */ +/* */ +/******************************************************************************/ +/******************* Bit definition for CORDIC_CSR register *****************/ +#define CORDIC_CSR_FUNC_Pos (0U) +#define CORDIC_CSR_FUNC_Msk (0xFUL << CORDIC_CSR_FUNC_Pos) /*!< 0x0000000F */ +#define CORDIC_CSR_FUNC CORDIC_CSR_FUNC_Msk /*!< Function */ +#define CORDIC_CSR_FUNC_0 (0x1UL << CORDIC_CSR_FUNC_Pos) /*!< 0x00000001 */ +#define CORDIC_CSR_FUNC_1 (0x2UL << CORDIC_CSR_FUNC_Pos) /*!< 0x00000002 */ +#define CORDIC_CSR_FUNC_2 (0x4UL << CORDIC_CSR_FUNC_Pos) /*!< 0x00000004 */ +#define CORDIC_CSR_FUNC_3 (0x8UL << CORDIC_CSR_FUNC_Pos) /*!< 0x00000008 */ +#define CORDIC_CSR_PRECISION_Pos (4U) +#define CORDIC_CSR_PRECISION_Msk (0xFUL << CORDIC_CSR_PRECISION_Pos) /*!< 0x000000F0 */ +#define CORDIC_CSR_PRECISION CORDIC_CSR_PRECISION_Msk /*!< Precision */ +#define CORDIC_CSR_PRECISION_0 (0x1UL << CORDIC_CSR_PRECISION_Pos) /*!< 0x00000010 */ +#define CORDIC_CSR_PRECISION_1 (0x2UL << CORDIC_CSR_PRECISION_Pos) /*!< 0x00000020 */ +#define CORDIC_CSR_PRECISION_2 (0x4UL << CORDIC_CSR_PRECISION_Pos) /*!< 0x00000040 */ +#define CORDIC_CSR_PRECISION_3 (0x8UL << CORDIC_CSR_PRECISION_Pos) /*!< 0x00000080 */ +#define CORDIC_CSR_SCALE_Pos (8U) +#define CORDIC_CSR_SCALE_Msk (0x7UL << CORDIC_CSR_SCALE_Pos) /*!< 0x00000700 */ +#define CORDIC_CSR_SCALE CORDIC_CSR_SCALE_Msk /*!< Scaling factor */ +#define CORDIC_CSR_SCALE_0 (0x1UL << CORDIC_CSR_SCALE_Pos) /*!< 0x00000100 */ +#define CORDIC_CSR_SCALE_1 (0x2UL << CORDIC_CSR_SCALE_Pos) /*!< 0x00000200 */ +#define CORDIC_CSR_SCALE_2 (0x4UL << CORDIC_CSR_SCALE_Pos) /*!< 0x00000400 */ +#define CORDIC_CSR_IEN_Pos (16U) +#define CORDIC_CSR_IEN_Msk (0x1UL << CORDIC_CSR_IEN_Pos) /*!< 0x00010000 */ +#define CORDIC_CSR_IEN CORDIC_CSR_IEN_Msk /*!< Interrupt Enable */ +#define CORDIC_CSR_DMAREN_Pos (17U) +#define CORDIC_CSR_DMAREN_Msk (0x1UL << CORDIC_CSR_DMAREN_Pos) /*!< 0x00020000 */ +#define CORDIC_CSR_DMAREN CORDIC_CSR_DMAREN_Msk /*!< DMA Read channel Enable */ +#define CORDIC_CSR_DMAWEN_Pos (18U) +#define CORDIC_CSR_DMAWEN_Msk (0x1UL << CORDIC_CSR_DMAWEN_Pos) /*!< 0x00040000 */ +#define CORDIC_CSR_DMAWEN CORDIC_CSR_DMAWEN_Msk /*!< DMA Write channel Enable */ +#define CORDIC_CSR_NRES_Pos (19U) +#define CORDIC_CSR_NRES_Msk (0x1UL << CORDIC_CSR_NRES_Pos) /*!< 0x00080000 */ +#define CORDIC_CSR_NRES CORDIC_CSR_NRES_Msk /*!< Number of results in WDATA register */ +#define CORDIC_CSR_NARGS_Pos (20U) +#define CORDIC_CSR_NARGS_Msk (0x1UL << CORDIC_CSR_NARGS_Pos) /*!< 0x00100000 */ +#define CORDIC_CSR_NARGS CORDIC_CSR_NARGS_Msk /*!< Number of arguments in RDATA register */ +#define CORDIC_CSR_RESSIZE_Pos (21U) +#define CORDIC_CSR_RESSIZE_Msk (0x1UL << CORDIC_CSR_RESSIZE_Pos) /*!< 0x00200000 */ +#define CORDIC_CSR_RESSIZE CORDIC_CSR_RESSIZE_Msk /*!< Width of output data */ +#define CORDIC_CSR_ARGSIZE_Pos (22U) +#define CORDIC_CSR_ARGSIZE_Msk (0x1UL << CORDIC_CSR_ARGSIZE_Pos) /*!< 0x00400000 */ +#define CORDIC_CSR_ARGSIZE CORDIC_CSR_ARGSIZE_Msk /*!< Width of input data */ +#define CORDIC_CSR_RRDY_Pos (31U) +#define CORDIC_CSR_RRDY_Msk (0x1UL << CORDIC_CSR_RRDY_Pos) /*!< 0x80000000 */ +#define CORDIC_CSR_RRDY CORDIC_CSR_RRDY_Msk /*!< Result Ready Flag */ + +/******************* Bit definition for CORDIC_WDATA register ***************/ +#define CORDIC_WDATA_ARG_Pos (0U) +#define CORDIC_WDATA_ARG_Msk (0xFFFFFFFFUL << CORDIC_WDATA_ARG_Pos) /*!< 0xFFFFFFFF */ +#define CORDIC_WDATA_ARG CORDIC_WDATA_ARG_Msk /*!< Input Argument */ + +/******************* Bit definition for CORDIC_RDATA register ***************/ +#define CORDIC_RDATA_RES_Pos (0U) +#define CORDIC_RDATA_RES_Msk (0xFFFFFFFFUL << CORDIC_RDATA_RES_Pos) /*!< 0xFFFFFFFF */ +#define CORDIC_RDATA_RES CORDIC_RDATA_RES_Msk /*!< Output Result */ + +/******************************************************************************/ +/* */ +/* CRC calculation unit */ +/* */ +/******************************************************************************/ +/******************* Bit definition for CRC_DR register *********************/ +#define CRC_DR_DR_Pos (0U) +#define CRC_DR_DR_Msk (0xFFFFFFFFUL << CRC_DR_DR_Pos) /*!< 0xFFFFFFFF */ +#define CRC_DR_DR CRC_DR_DR_Msk /*!< Data register bits */ + +/******************* Bit definition for CRC_IDR register ********************/ +#define CRC_IDR_IDR_Pos (0U) +#define CRC_IDR_IDR_Msk (0xFFFFFFFFUL << CRC_IDR_IDR_Pos) /*!< 0xFFFFFFFF */ +#define CRC_IDR_IDR CRC_IDR_IDR_Msk /*!< General-purpose 32-bit data register bits */ + +/******************** Bit definition for CRC_CR register ********************/ +#define CRC_CR_RESET_Pos (0U) +#define CRC_CR_RESET_Msk (0x1UL << CRC_CR_RESET_Pos) /*!< 0x00000001 */ +#define CRC_CR_RESET CRC_CR_RESET_Msk /*!< RESET the CRC computation unit bit */ +#define CRC_CR_POLYSIZE_Pos (3U) +#define CRC_CR_POLYSIZE_Msk (0x3UL << CRC_CR_POLYSIZE_Pos) /*!< 0x00000018 */ +#define CRC_CR_POLYSIZE CRC_CR_POLYSIZE_Msk /*!< Polynomial size bits */ +#define CRC_CR_POLYSIZE_0 (0x1UL << CRC_CR_POLYSIZE_Pos) /*!< 0x00000008 */ +#define CRC_CR_POLYSIZE_1 (0x2UL << CRC_CR_POLYSIZE_Pos) /*!< 0x00000010 */ +#define CRC_CR_REV_IN_Pos (5U) +#define CRC_CR_REV_IN_Msk (0x3UL << CRC_CR_REV_IN_Pos) /*!< 0x00000060 */ +#define CRC_CR_REV_IN CRC_CR_REV_IN_Msk /*!< REV_IN Reverse Input Data bits */ +#define CRC_CR_REV_IN_0 (0x1UL << CRC_CR_REV_IN_Pos) /*!< 0x00000020 */ +#define CRC_CR_REV_IN_1 (0x2UL << CRC_CR_REV_IN_Pos) /*!< 0x00000040 */ +#define CRC_CR_REV_OUT_Pos (7U) +#define CRC_CR_REV_OUT_Msk (0x1UL << CRC_CR_REV_OUT_Pos) /*!< 0x00000080 */ +#define CRC_CR_REV_OUT CRC_CR_REV_OUT_Msk /*!< REV_OUT Reverse Output Data bits */ + +/******************* Bit definition for CRC_INIT register *******************/ +#define CRC_INIT_INIT_Pos (0U) +#define CRC_INIT_INIT_Msk (0xFFFFFFFFUL << CRC_INIT_INIT_Pos) /*!< 0xFFFFFFFF */ +#define CRC_INIT_INIT CRC_INIT_INIT_Msk /*!< Initial CRC value bits */ + +/******************* Bit definition for CRC_POL register ********************/ +#define CRC_POL_POL_Pos (0U) +#define CRC_POL_POL_Msk (0xFFFFFFFFUL << CRC_POL_POL_Pos) /*!< 0xFFFFFFFF */ +#define CRC_POL_POL CRC_POL_POL_Msk /*!< Coefficients of the polynomial */ + +/******************************************************************************/ +/* */ +/* CRS Clock Recovery System */ +/******************************************************************************/ + +/******************* Bit definition for CRS_CR register *********************/ +#define CRS_CR_SYNCOKIE_Pos (0U) +#define CRS_CR_SYNCOKIE_Msk (0x1UL << CRS_CR_SYNCOKIE_Pos) /*!< 0x00000001 */ +#define CRS_CR_SYNCOKIE CRS_CR_SYNCOKIE_Msk /*!< SYNC event OK interrupt enable */ +#define CRS_CR_SYNCWARNIE_Pos (1U) +#define CRS_CR_SYNCWARNIE_Msk (0x1UL << CRS_CR_SYNCWARNIE_Pos) /*!< 0x00000002 */ +#define CRS_CR_SYNCWARNIE CRS_CR_SYNCWARNIE_Msk /*!< SYNC warning interrupt enable */ +#define CRS_CR_ERRIE_Pos (2U) +#define CRS_CR_ERRIE_Msk (0x1UL << CRS_CR_ERRIE_Pos) /*!< 0x00000004 */ +#define CRS_CR_ERRIE CRS_CR_ERRIE_Msk /*!< SYNC error or trimming error interrupt enable */ +#define CRS_CR_ESYNCIE_Pos (3U) +#define CRS_CR_ESYNCIE_Msk (0x1UL << CRS_CR_ESYNCIE_Pos) /*!< 0x00000008 */ +#define CRS_CR_ESYNCIE CRS_CR_ESYNCIE_Msk /*!< Expected SYNC interrupt enable */ +#define CRS_CR_CEN_Pos (5U) +#define CRS_CR_CEN_Msk (0x1UL << CRS_CR_CEN_Pos) /*!< 0x00000020 */ +#define CRS_CR_CEN CRS_CR_CEN_Msk /*!< Frequency error counter enable */ +#define CRS_CR_AUTOTRIMEN_Pos (6U) +#define CRS_CR_AUTOTRIMEN_Msk (0x1UL << CRS_CR_AUTOTRIMEN_Pos) /*!< 0x00000040 */ +#define CRS_CR_AUTOTRIMEN CRS_CR_AUTOTRIMEN_Msk /*!< Automatic trimming enable */ +#define CRS_CR_SWSYNC_Pos (7U) +#define CRS_CR_SWSYNC_Msk (0x1UL << CRS_CR_SWSYNC_Pos) /*!< 0x00000080 */ +#define CRS_CR_SWSYNC CRS_CR_SWSYNC_Msk /*!< Generate software SYNC event */ +#define CRS_CR_TRIM_Pos (8U) +#define CRS_CR_TRIM_Msk (0x7FUL << CRS_CR_TRIM_Pos) /*!< 0x00007F00 */ +#define CRS_CR_TRIM CRS_CR_TRIM_Msk /*!< HSI48 oscillator smooth trimming */ + +/******************* Bit definition for CRS_CFGR register *********************/ +#define CRS_CFGR_RELOAD_Pos (0U) +#define CRS_CFGR_RELOAD_Msk (0xFFFFUL << CRS_CFGR_RELOAD_Pos) /*!< 0x0000FFFF */ +#define CRS_CFGR_RELOAD CRS_CFGR_RELOAD_Msk /*!< Counter reload value */ +#define CRS_CFGR_FELIM_Pos (16U) +#define CRS_CFGR_FELIM_Msk (0xFFUL << CRS_CFGR_FELIM_Pos) /*!< 0x00FF0000 */ +#define CRS_CFGR_FELIM CRS_CFGR_FELIM_Msk /*!< Frequency error limit */ + +#define CRS_CFGR_SYNCDIV_Pos (24U) +#define CRS_CFGR_SYNCDIV_Msk (0x7UL << CRS_CFGR_SYNCDIV_Pos) /*!< 0x07000000 */ +#define CRS_CFGR_SYNCDIV CRS_CFGR_SYNCDIV_Msk /*!< SYNC divider */ +#define CRS_CFGR_SYNCDIV_0 (0x1UL << CRS_CFGR_SYNCDIV_Pos) /*!< 0x01000000 */ +#define CRS_CFGR_SYNCDIV_1 (0x2UL << CRS_CFGR_SYNCDIV_Pos) /*!< 0x02000000 */ +#define CRS_CFGR_SYNCDIV_2 (0x4UL << CRS_CFGR_SYNCDIV_Pos) /*!< 0x04000000 */ + +#define CRS_CFGR_SYNCSRC_Pos (28U) +#define CRS_CFGR_SYNCSRC_Msk (0x3UL << CRS_CFGR_SYNCSRC_Pos) /*!< 0x30000000 */ +#define CRS_CFGR_SYNCSRC CRS_CFGR_SYNCSRC_Msk /*!< SYNC signal source selection */ +#define CRS_CFGR_SYNCSRC_0 (0x1UL << CRS_CFGR_SYNCSRC_Pos) /*!< 0x10000000 */ +#define CRS_CFGR_SYNCSRC_1 (0x2UL << CRS_CFGR_SYNCSRC_Pos) /*!< 0x20000000 */ + +#define CRS_CFGR_SYNCPOL_Pos (31U) +#define CRS_CFGR_SYNCPOL_Msk (0x1UL << CRS_CFGR_SYNCPOL_Pos) /*!< 0x80000000 */ +#define CRS_CFGR_SYNCPOL CRS_CFGR_SYNCPOL_Msk /*!< SYNC polarity selection */ + +/******************* Bit definition for CRS_ISR register *********************/ +#define CRS_ISR_SYNCOKF_Pos (0U) +#define CRS_ISR_SYNCOKF_Msk (0x1UL << CRS_ISR_SYNCOKF_Pos) /*!< 0x00000001 */ +#define CRS_ISR_SYNCOKF CRS_ISR_SYNCOKF_Msk /*!< SYNC event OK flag */ +#define CRS_ISR_SYNCWARNF_Pos (1U) +#define CRS_ISR_SYNCWARNF_Msk (0x1UL << CRS_ISR_SYNCWARNF_Pos) /*!< 0x00000002 */ +#define CRS_ISR_SYNCWARNF CRS_ISR_SYNCWARNF_Msk /*!< SYNC warning flag */ +#define CRS_ISR_ERRF_Pos (2U) +#define CRS_ISR_ERRF_Msk (0x1UL << CRS_ISR_ERRF_Pos) /*!< 0x00000004 */ +#define CRS_ISR_ERRF CRS_ISR_ERRF_Msk /*!< Error flag */ +#define CRS_ISR_ESYNCF_Pos (3U) +#define CRS_ISR_ESYNCF_Msk (0x1UL << CRS_ISR_ESYNCF_Pos) /*!< 0x00000008 */ +#define CRS_ISR_ESYNCF CRS_ISR_ESYNCF_Msk /*!< Expected SYNC flag */ +#define CRS_ISR_SYNCERR_Pos (8U) +#define CRS_ISR_SYNCERR_Msk (0x1UL << CRS_ISR_SYNCERR_Pos) /*!< 0x00000100 */ +#define CRS_ISR_SYNCERR CRS_ISR_SYNCERR_Msk /*!< SYNC error */ +#define CRS_ISR_SYNCMISS_Pos (9U) +#define CRS_ISR_SYNCMISS_Msk (0x1UL << CRS_ISR_SYNCMISS_Pos) /*!< 0x00000200 */ +#define CRS_ISR_SYNCMISS CRS_ISR_SYNCMISS_Msk /*!< SYNC missed */ +#define CRS_ISR_TRIMOVF_Pos (10U) +#define CRS_ISR_TRIMOVF_Msk (0x1UL << CRS_ISR_TRIMOVF_Pos) /*!< 0x00000400 */ +#define CRS_ISR_TRIMOVF CRS_ISR_TRIMOVF_Msk /*!< Trimming overflow or underflow */ +#define CRS_ISR_FEDIR_Pos (15U) +#define CRS_ISR_FEDIR_Msk (0x1UL << CRS_ISR_FEDIR_Pos) /*!< 0x00008000 */ +#define CRS_ISR_FEDIR CRS_ISR_FEDIR_Msk /*!< Frequency error direction */ +#define CRS_ISR_FECAP_Pos (16U) +#define CRS_ISR_FECAP_Msk (0xFFFFUL << CRS_ISR_FECAP_Pos) /*!< 0xFFFF0000 */ +#define CRS_ISR_FECAP CRS_ISR_FECAP_Msk /*!< Frequency error capture */ + +/******************* Bit definition for CRS_ICR register *********************/ +#define CRS_ICR_SYNCOKC_Pos (0U) +#define CRS_ICR_SYNCOKC_Msk (0x1UL << CRS_ICR_SYNCOKC_Pos) /*!< 0x00000001 */ +#define CRS_ICR_SYNCOKC CRS_ICR_SYNCOKC_Msk /*!< SYNC event OK clear flag */ +#define CRS_ICR_SYNCWARNC_Pos (1U) +#define CRS_ICR_SYNCWARNC_Msk (0x1UL << CRS_ICR_SYNCWARNC_Pos) /*!< 0x00000002 */ +#define CRS_ICR_SYNCWARNC CRS_ICR_SYNCWARNC_Msk /*!< SYNC warning clear flag */ +#define CRS_ICR_ERRC_Pos (2U) +#define CRS_ICR_ERRC_Msk (0x1UL << CRS_ICR_ERRC_Pos) /*!< 0x00000004 */ +#define CRS_ICR_ERRC CRS_ICR_ERRC_Msk /*!< Error clear flag */ +#define CRS_ICR_ESYNCC_Pos (3U) +#define CRS_ICR_ESYNCC_Msk (0x1UL << CRS_ICR_ESYNCC_Pos) /*!< 0x00000008 */ +#define CRS_ICR_ESYNCC CRS_ICR_ESYNCC_Msk /*!< Expected SYNC clear flag */ + +/******************************************************************************/ +/* */ +/* Digital to Analog Converter */ +/* */ +/******************************************************************************/ +/* + * @brief Specific device feature definitions (not present on all devices in the STM32G4 series) + */ +#define DAC_CHANNEL2_SUPPORT /*!< DAC feature available only on specific devices: DAC channel 2 available */ + +/******************** Bit definition for DAC_CR register ********************/ +#define DAC_CR_EN1_Pos (0U) +#define DAC_CR_EN1_Msk (0x1UL << DAC_CR_EN1_Pos) /*!< 0x00000001 */ +#define DAC_CR_EN1 DAC_CR_EN1_Msk /*!*/ +#define DAC_CR_CEN1_Pos (14U) +#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ +#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ + +#define DAC_CR_HFSEL_Pos (15U) +#define DAC_CR_HFSEL_Msk (0x1UL << DAC_CR_HFSEL_Pos) /*!< 0x00008000 */ +#define DAC_CR_HFSEL DAC_CR_HFSEL_Msk /*!*/ + +#define DAC_CR_EN2_Pos (16U) +#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ +#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ +#define DAC_CR_CEN2_Pos (30U) +#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ +#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ + +/***************** Bit definition for DAC_SWTRIGR register ******************/ +#define DAC_SWTRIGR_SWTRIG1_Pos (0U) +#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ +#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!CPACR |= ((3UL << (10*2))|(3UL << (11*2))); /* set CP10 and CP11 Full Access */ + #endif + + /* Configure the Vector Table location add offset address ------------------*/ +#if defined(USER_VECT_TAB_ADDRESS) + SCB->VTOR = VECT_TAB_BASE_ADDRESS | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ +#endif /* USER_VECT_TAB_ADDRESS */ +} + +/** + * @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/divided by the PLL factors. + * + * (**) HSI_VALUE is a constant defined in stm32g4xx_hal.h file (default value + * 16 MHz) but the real value may vary depending on the variations + * in voltage and temperature. + * + * (***) HSE_VALUE is a constant defined in stm32g4xx_hal.h file (default value + * 24 MHz), 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, pllvco, pllr, pllsource, pllm; + + /* Get SYSCLK source -------------------------------------------------------*/ + switch (RCC->CFGR & RCC_CFGR_SWS) + { + case 0x04: /* HSI used as system clock source */ + SystemCoreClock = HSI_VALUE; + break; + + case 0x08: /* HSE used as system clock source */ + SystemCoreClock = HSE_VALUE; + break; + + case 0x0C: /* PLL used as system clock source */ + /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLLM) * PLLN + SYSCLK = PLL_VCO / PLLR + */ + pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC); + pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4) + 1U ; + if (pllsource == 0x02UL) /* HSI used as PLL clock source */ + { + pllvco = (HSI_VALUE / pllm); + } + else /* HSE used as PLL clock source */ + { + pllvco = (HSE_VALUE / pllm); + } + pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8); + pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25) + 1U) * 2U; + SystemCoreClock = pllvco/pllr; + break; + + default: + break; + } + /* Compute HCLK clock frequency --------------------------------------------*/ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + + +/** + * @} + */ + +/** + * @} + */ + +/** + * @} + */ + + diff --git a/system_stm32g4xx.h b/system_stm32g4xx.h new file mode 100644 index 0000000..ed341a8 --- /dev/null +++ b/system_stm32g4xx.h @@ -0,0 +1,104 @@ +/** + ****************************************************************************** + * @file system_stm32g4xx.h + * @author MCD Application Team + * @brief CMSIS Cortex-M4 Device System Source File for STM32G4xx devices. + ****************************************************************************** + * @attention + * + * Copyright (c) 2019 STMicroelectronics. + * All rights reserved. + * + * This software is licensed under terms that can be found in the LICENSE file + * in the root directory of this software component. + * If no LICENSE file comes with this software, it is provided AS-IS. + * + ****************************************************************************** + */ + +/** @addtogroup CMSIS + * @{ + */ + +/** @addtogroup stm32g4xx_system + * @{ + */ + +/** + * @brief Define to prevent recursive inclusion + */ +#ifndef __SYSTEM_STM32G4XX_H +#define __SYSTEM_STM32G4XX_H + +#ifdef __cplusplus + extern "C" { +#endif + +/** @addtogroup STM32G4xx_System_Includes + * @{ + */ + +/** + * @} + */ + + +/** @addtogroup STM32G4xx_System_Exported_Variables + * @{ + */ + /* The SystemCoreClock variable is updated in three ways: + 1) by calling CMSIS function SystemCoreClockUpdate() + 2) by calling HAL API function HAL_RCC_GetSysClockFreq() + 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency + Note: If you use this function to configure the system clock; then there + is no need to call the 2 first functions listed above, since SystemCoreClock + variable is updated automatically. + */ +extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ + +extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ +extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ + +/** + * @} + */ + +/** @addtogroup STM32G4xx_System_Exported_Constants + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32G4xx_System_Exported_Macros + * @{ + */ + +/** + * @} + */ + +/** @addtogroup STM32G4xx_System_Exported_Functions + * @{ + */ + +extern void SystemInit(void); +extern void SystemCoreClockUpdate(void); +/** + * @} + */ + +#ifdef __cplusplus +} +#endif + +#endif /*__SYSTEM_STM32G4XX_H */ + +/** + * @} + */ + +/** + * @} + */ diff --git a/utils/filt.cpp b/utils/filt.cpp new file mode 100644 index 0000000..46cf1e7 --- /dev/null +++ b/utils/filt.cpp @@ -0,0 +1,67 @@ +#include + +#include "filt.h" + +float FilterGPS::Limit(float Value, float Min, float Max) +{ + if (Value > Max) return Max; + if (Value < Min) return Min; + return Value; +} + +float FilterGPS::Minimum(float Value1, float Value2) +{ + if (Value1 < Value2) return Value1; + return Value2; +} + +void FilterGPS::Update(bool valid, float gps, float acc) +{ + const float ga = 9.80665f; + + Delay.Acc[Delay.Index] = acc; + Delay.Pos[Delay.Index] = Position.Value; + Delay.Spd[Delay.Index++] = Speed.Value; + if (Delay.Index >= Delay.Size) Delay.Index = 0; + + float prev = Delay.Acc[Delay.Index]; + float shift = gps - Delay.Pos[Delay.Index]; + + float coef_a = 1; + if (Position.EnAcc) coef_a = Position.Acc / fabsf(prev); + float coef_p = 1; + if (Position.EnGPS) coef_p = powf(fabsf(shift * Position.Length), Position.Width); + + float coef1 = Minimum(coef_a, coef_p); + coef1 = Limit(coef1, Position.Min, Position.Max); + + Speed.Count++; + if (valid) + { + Speed.ValueGPS = (gps - Speed.Last_GPS) * Freq / Speed.Count; + Speed.Last_GPS = gps; + Speed.ValueAccGPS= (Speed.ValueGPS- Speed.Speed_GPS) * Freq / Speed.Count; + Speed.Speed_GPS = Speed.ValueGPS; + Speed.Count = 0; + } + + for (int a = 0; a < Delay.Size; a++) Delay.Pos[a] += shift * coef1; + Position.Value += shift * coef1 + (Speed.Value / Freq) * (1 - coef1); + + // SPEED + + shift = Speed.ValueGPS - Delay.Spd[Delay.Index]; + + coef_a = 1; + if (Speed.EnAcc) coef_a = Speed.Acc / fabsf(prev); + float coef_g = 1; + if (Speed.EnAcc) coef_g = Speed.AccGPS / fabsf(Speed.ValueAccGPS); + float coef_s = 1; + if (Speed.EnGPS) coef_s = powf(fabsf(shift * Speed.Length), Speed.Width); + + float coef2 = Minimum(coef_a, Minimum(coef_s, coef_g)); + coef2 = Limit(coef2, Speed.Min, Speed.Max); + + for (int a = 0; a < Delay.Size; a++) Delay.Spd[a] += shift * coef2; + Speed.Value += shift * coef2 + (acc * ga / Freq) * (1 - coef2); +} diff --git a/utils/filt.h b/utils/filt.h new file mode 100644 index 0000000..d861b12 --- /dev/null +++ b/utils/filt.h @@ -0,0 +1,56 @@ +#pragma once +class FilterGPS +{ + public: + + float Freq=100; + + struct + { + float Value=0; + //--- + float Min=0.0001, Max=0.1; + //--- + bool EnAcc=true; + float Acc=0.02; + //--- + bool EnGPS=true; + float Width=2, Length=1; + //--- + }Position; + + struct + { + float ValueAccGPS=0; + float ValueGPS=0; + float Value=0; + //--- + float Min=0.0001, Max=0.1; + //--- + bool EnAcc=true; + float Acc=0.02; + float AccGPS=0.02; + //--- + bool EnGPS=true; + float Width=2, Length=1; + //--- + float Last_GPS=0, Speed_GPS=0; + long Count=0; + }Speed; + + struct + { + float Pos[50]; + float Acc[50]; + float Spd[50]; + long Size=30, Index=0; + }Delay; + + void Update(bool valid, float gps, float acc); + + private: + + float Limit(float Value, float Min, float Max); + float Minimum(float Value1, float Value2); + +}; diff --git a/utils/med.cpp b/utils/med.cpp new file mode 100644 index 0000000..e368fa8 --- /dev/null +++ b/utils/med.cpp @@ -0,0 +1,72 @@ +#include + +#include "med.h" + +long MED_Update(long Value, MED_Data16& Data) +{ + Data.Buf[Data.Index++] = Value; + if (Data.Index >= Data.Size) Data.Index = 0; + + memcpy(Data.Temp, Data.Buf, Data.Size * sizeof(short)); + + short* t = Data.Temp; + long s = Data.Size; + + for (long a = 0; a < s; a++) + for (long b = a; b < s; b++) + { + if (t[a] <= t[b]) continue; + short v = t[a]; + t[a] = t[b]; + t[b] = v; + } + + return t[s / 2]; +} +//------------------------------------------------------------------------------ + +long MED_Update(long Value, MED_Data32& Data) +{ + Data.Buf[Data.Index++] = Value; + if (Data.Index >= Data.Size) Data.Index = 0; + + memcpy(Data.Temp, Data.Buf, Data.Size * sizeof(long)); + + long* t = Data.Temp; + long s = Data.Size; + + for (long a = 0; a < s; a++) + for (long b = a; b < s; b++) + { + if (t[a] <= t[b]) continue; + long v = t[a]; + t[a] = t[b]; + t[b] = v; + } + + return t[s / 2]; +} +//------------------------------------------------------------------------------ + +float MED_Update(float Value, MED_DataF32& Data) +{ + Data.Buf[Data.Index++] = Value; + if (Data.Index >= Data.Size) Data.Index = 0; + + memcpy(Data.Temp, Data.Buf, Data.Size * sizeof(float)); + + float* t = Data.Temp; + long s = Data.Size; + + for (long a = 0; a < s; a++) + for (long b = a; b < s; b++) + { + if (t[a] <= t[b]) continue; + float v = t[a]; + t[a] = t[b]; + t[b] = v; + } + + return t[s / 2]; +} +//------------------------------------------------------------------------------ diff --git a/utils/med.h b/utils/med.h new file mode 100644 index 0000000..29b52fd --- /dev/null +++ b/utils/med.h @@ -0,0 +1,23 @@ +#pragma once + +struct MED_Data16 +{ + short Size, Index; + short *Buf, *Temp; +}; + +struct MED_Data32 +{ + long Size, Index; + long *Buf, *Temp; +}; + +struct MED_DataF32 +{ + long Size, Index; + float *Buf, *Temp; +}; + +long MED_Update(long Value, MED_Data16& Data); +long MED_Update(long Value, MED_Data32& Data); +float MED_Update(float Value, MED_DataF32& Data); diff --git a/utils/med2.cpp b/utils/med2.cpp new file mode 100644 index 0000000..79f5200 --- /dev/null +++ b/utils/med2.cpp @@ -0,0 +1,58 @@ +#include + +#include "med2.h" + +void MED2_Init(MED2_Data& Data) +{ + for (unsigned char a = 0; a < Data.Size; a++) { Data.Index[a] = a; Data.Buff[a] = 0; } + Data.Last = 0; +} + +long MED2_Update(long Value, MED2_Data& Data) +{ + unsigned char* index=Data.Index; + unsigned char size=Data.Size; + unsigned char& last=Data.Last; + long* buff=Data.Buff; + //--- + buff[last] = Value; + //--- + unsigned char id; + for (id = 0; id < size; id++) if (index[id] == last) break; + //--- + bool f = (!id || (Value > buff[index[id - 1]])); + + if (f) + { + for (unsigned char a = id; a < size - 1; a++) + { + if (buff[index[a + 1]] >= Value) break; + unsigned char tmp = index[a]; + index[a] = index[a + 1]; + index[a + 1] = tmp; + } + } + else + { + for (unsigned char a = id; a > 0; a--) + { + if (buff[index[a - 1]] <= Value) break; + unsigned char tmp = index[a - 1]; + index[a - 1] = index[a]; + index[a] = tmp; + } + } + + last++; + if (last >= size) last = 0; + + if(Data.Smooth>1) + { + long ret=0; + long s = Data.Smooth/2; + for(long a=-s; a500) pwm[a]=500; + else if(pwm[a]<-500) pwm[a]=-500; + //--- + if(min>pwm[a]) min=pwm[a]; + if(max0) throt-=up; + if(down<0) throt-=down; + + for(int a=0; a + +#include "quat.h" + +static const float PI = 3.14159265359f; +static const float TO_DEG = 180.0f/PI; +static const float TO_RAD = PI/180.0f; + +Vec3 Motion(Vec3 vec, bool move, float dx, float dy, float range, unsigned long time) +{ + //static float move_x=0, move_y=0; + + //static float move_tof_x=0, move_tof_y=0; + //static float move_flo_x=0, move_flo_y=0; + + /*static long timer=0; + timer++; + if(timer>1000) + { + move_flo_x=move_flo_y=move_tof_x=move_tof_y=0; + move_x=0; move_y=0; + timer=0; + }*/ + + //if(!move) return {0,0,0}; + + static float len, high; + high = range * vec.z; // cos(Z) + len = range * sqrtf(1-vec.z*vec.z); // sin(Z) + + static float a_x=0, a_y=0; + a_x=0, a_y=0; + + static float v_x, v_y; + + static float angle_shift=600; + + if(move) + { + a_x = (v_x-vec.x)*angle_shift; + a_y = (v_y-vec.y)*angle_shift; + } + + v_x=vec.x; + v_y=vec.y; + + static Vec3 v; + + float x=(dx+a_x), y=(dy-a_y); + + static float fx=0, fy=0; + + //fx=(fx*3+x)/4; + //fy=(fy*3+y)/4; + + return {x, y, high}; + + //v = RotateToZ({dx-a_x, dy-a_y, 0}); + + //v = RotateToZ({(dx+a_x)*(range/1000.0f), (dy-a_y)*(range/1000.0f), 0}, true); + + //v = RotateToZ({1000, 0, 0}, true); + //v = RotateToZ({(dx+a_x)*(range/1000.0f), 0, 0}, true); + + //v={dx+a_x, dy-a_y, 0}; + + //move_x-=v.x; + //move_y-=v.y; + + + //move_flo_x+=dx; + //move_flo_y+=dy; + + //move_tof_x+=(float)a_x; + //move_tof_y+=(float)a_y; + + return v; + +} + +/*void Motion(Vec3 vec, short dx, short dy, float range, unsigned long time) +{ + static long move_x=0, move_y=0; + + move_x+=dx; + move_y+=dy; + + static float len, high; + high = range * vec.z; // cos(Z) + len = range * sqrtf(1-vec.z*vec.z); // sin(Z) + + static float a_x, a_y; + + a_x = range * vec.x; + a_y = -range * vec.y; + + static float m_x, m_y; + + m_x=move_x+a_x; + m_y=move_y+a_y; +}*/ diff --git a/utils/move.h b/utils/move.h new file mode 100644 index 0000000..6bfd79a --- /dev/null +++ b/utils/move.h @@ -0,0 +1,5 @@ +#pragma once + +#include "quat.h" + +Vec3 Motion(Vec3 vec, bool move, float dx, float dy, float range, unsigned long time); \ No newline at end of file diff --git a/utils/pid.cpp b/utils/pid.cpp new file mode 100644 index 0000000..532424b --- /dev/null +++ b/utils/pid.cpp @@ -0,0 +1,28 @@ +#include "pid.h" + +static inline float Saturation(float val, float min, float max) +{ + if (val < min) val = min; + if (val > max) val = max; + return val; +} + +float PID_Update(float Value, float Current, PID_Data& Coef, float de) +{ + float p, i, d; + + float e = Value - Current; + + p = e * Coef.P.C; + p = Saturation(p, Coef.P.Min, Coef.P.Max); + + i = Coef.i; + i += e * Coef.I.C; + i = Saturation(i, Coef.I.Min, Coef.I.Max); + Coef.i = i; + + d = de * Coef.D.C; + d = Saturation(d, Coef.D.Min, Coef.D.Max); + + return Saturation(p + i + d, Coef.Min, Coef.Max); +} diff --git a/utils/pid.h b/utils/pid.h new file mode 100644 index 0000000..fb25bbd --- /dev/null +++ b/utils/pid.h @@ -0,0 +1,14 @@ +#pragma once + +struct PID_Data +{ + float Min, Max; + struct + { + float Min, Max; + float C; + }P,I,D; + float i = 0; +}; + +float PID_Update(float Value, float Current, PID_Data& Coef, float de); diff --git a/utils/prot.cpp b/utils/prot.cpp new file mode 100644 index 0000000..6ab9678 --- /dev/null +++ b/utils/prot.cpp @@ -0,0 +1,593 @@ +#include + +#include "tick.h" + +#include "ori.h" + +#include "uart.h" +#include "gps.h" + +#include "pwm.h" + +#include "quat.h" + +#include "prot.h" +#include "prot_head.h" + +Point PointGPS{0,0,0}; + +MAIN_FLY_MODE MainFlyMode=MAIN_FLY_MODE::WAIT; + +STATUS_MODE Main_StatusMode; +SYS_MODE Main_SysMode; + +const unsigned char SRC_ID = 1; +const unsigned char DST_ID = 254; + +bool HeaderBegin::CheckCRC() +{ + unsigned char test = 0; + for (unsigned short a = 0; a < len1; a++) test ^= data[a]; + return crc == test; +} + +void HeaderBegin::SetCRC() +{ + unsigned char test = 0; + for (unsigned short a = 0; a < len1; a++) test ^= data[a]; + crc = test; +} + +enum class DataMode : unsigned char { Begin, Head, Data }; + +static unsigned char ProtoData[MaxLength]; +static DataMode Mode = DataMode::Begin; +static unsigned long Length, Index; + +static const unsigned long Wait = 100; // ms +static unsigned long Timer; + +static void ProcessingMessage(HeaderMessages*); + +bool MainUpdate(unsigned char byte) +{ + const unsigned long tick = TICK_GetCount(); + + //if ((tick - Timer > 100)) // ?????? ?????? ????????? + //{ + // printf("------------> Warning: %d\n", tick - Timer); + //} + + if ((Mode != DataMode::Begin) && (tick - Timer > Wait)) + { + Mode = DataMode::Begin; + //printf("Error: timeout\n"); + } + + Timer = tick; + + switch (Mode) + { + case DataMode::Begin: + { + if (byte != Global_stx) return true; + + Index = 0; + ProtoData[Index++] = byte; + Length = sizeof(HeaderBegin); + Mode = DataMode::Head; + + return true; + } + + case DataMode::Head: + { + ProtoData[Index++] = byte; + if (Index < Length) return true; + + HeaderBegin& begin = *(HeaderBegin*)ProtoData; + + if ((begin.len1 != begin.len2) || (begin.len1 > MaxLength) + || (begin.len1 < sizeof(HeaderMessages)) || Index < sizeof(HeaderBegin)) + { + //printf("Error: HeaderBegin -> size=%d\n", begin.len1); + Mode = DataMode::Begin; + return true; + } + + Mode = DataMode::Data; + Length += begin.len1; + + return true; + } + + case DataMode::Data: + { + ProtoData[Index++] = byte; + if (Index < Length) return true; + + HeaderBegin& begin = *(HeaderBegin*)ProtoData; + Mode = DataMode::Begin; + if (!begin.CheckCRC()) + { + //printf("Error: HeaderBegin -> CRC\n"); + return true; + } + ProcessingMessage((HeaderMessages*)(ProtoData + sizeof(HeaderBegin))); + return true; + } + } + + return false; +} + +void SendMes(HeaderBegin* begin) +{ + begin->SetCRC(); + //SendData(begin, sizeof(HeaderBegin) + begin->len1); + + UART2_Send(begin, sizeof(HeaderBegin) + begin->len1); +} +//??????? ???????? ????????? ????????? + +static unsigned char MessageData[MaxLength]; + +void* CreateMessageHeaders(HeaderBegin*& begin, unsigned long size, MESSAGES_ID msg_id) +{ + + begin = (HeaderBegin*)MessageData; + begin->len1 = begin->len2 = sizeof(HeaderMessages) + size; + begin->stx = Global_stx; + HeaderMessages& message = *(HeaderMessages*)begin->data; + message.msgId = msg_id; + message.srcId = SRC_ID; + message.dstId = DST_ID; + message.len = size; + message.timeusec = TICK_GetCount(); + + return message.data; +} +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? BatteryInfo +void BatteryInfo() +{ + //????? ???????? ? ?????? + HeaderBegin* begin; + PayloadBatteryInfo& info = *(PayloadBatteryInfo*) CreateMessageHeaders(begin, sizeof(PayloadBatteryInfo), MESSAGES_ID::BatteryInfo); + + info.perCharge = 95; + info.voltage = 14.5f; + info.amperage = 20.8f; + info.temp = 36.6f; + info.totalPower = 100.0f; + info.timeRemaining = 3600; + //printf("MessageTelemetry: BatteryInfo -> Send\n"); + SendMes(begin); +} + +NAV_SYS_MODE PROT_Nav=NAV_SYS_MODE::gps; + +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? SysInfo +void SysInfo() +{ + //????? ???????? ? ?????? + unsigned int count_engine = 4; + HeaderBegin* begin; + PayloadSysInfo& info = *(PayloadSysInfo*)CreateMessageHeaders(begin, sizeof(PayloadSysInfo) + count_engine * sizeof(EnginePowerInfo), MESSAGES_ID::SysInfo); + + info.mode = Main_SysMode; // !!!!!!!!!!!! + info.navSys = PROT_Nav; + info.pressureBaro = DataORI.Bar.Bar; + info.statusMode = Main_StatusMode; // !!!!!!!!!! + info.engineStatus = PWM_Enable ? ENGINE_STATUS::enable : ENGINE_STATUS::disable; // !!!!!!!!!!! + info.engineCount = count_engine; + info.tempBaro = DataORI.Temp.Bar; + + for (int i = 0; i < info.engineCount; i++) + { + EnginePowerInfo& pow = info.enginePower[i]; + pow.power = 50; + pow.current = 1.0; + pow.engineSpeed = 100; + pow.voltage = 12.5; + pow.temp = 34.5; + } + //printf("MessageTelemetry: SysInfo -> Send\n"); + + SendMes(begin); +} +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? GyroInfo +void GyroInfo() +{ + //????? ???????? ? ?????? + HeaderBegin* begin; + PayloadGyroInfo& info = *(PayloadGyroInfo*)CreateMessageHeaders(begin, sizeof(PayloadGyroInfo), MESSAGES_ID::GyroInfo); + + info.pitchGyroVel = DataORI.Gyr.X; + info.rollGyroVel = DataORI.Gyr.Y; + info.yawGyroVel = DataORI.Gyr.Z; + //printf("MessageTelemetry: GyroInfo -> Send\n"); + SendMes(begin); +} +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? AccelInfo +void AccelInfo() +{ + //????? ???????? ? ?????? + HeaderBegin* begin; + PayloadAccelInfo& info = *(PayloadAccelInfo*)CreateMessageHeaders(begin, sizeof(PayloadAccelInfo), MESSAGES_ID::AccelInfo); + + info.aX = DataORI.Acc.X; + info.aY = DataORI.Acc.Y; + info.aZ = DataORI.Acc.Z; + info.pitchAccelVel = 0.0; + info.rollAccelVel = 0.0; + info.yawAccelVel = 0.0; + info.tempAccel = DataORI.Temp.Acc; + //printf("MessageTelemetry: AccelInfo -> Send\n"); + SendMes(begin); +} + +static GPS_BaseInfo Main_GPS; + +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? GpsInfo +void GpsInfo() +{ + + GPS_GetBaseInfo(Main_GPS); + + //????? ???????? ? ?????? + HeaderBegin* begin; + PayloadGpsInfo& info = *(PayloadGpsInfo*)CreateMessageHeaders(begin, sizeof(PayloadGpsInfo), MESSAGES_ID::GpsInfo); + + info.lat = Main_GPS.lat; + info.lon = Main_GPS.lon; + info.absAlt = Main_GPS.absAlt; + info.realAlt = Main_GPS.realAlt; + info.fixType = Main_GPS.fixType; + info.hdop = Main_GPS.hdop; + info.pdop = Main_GPS.pdop; + info.vdop = Main_GPS.vdop; + info.satUsed = Main_GPS.satUsed; + info.satVisible = Main_GPS.satVisible; + info.noise = Main_GPS.noise; + info.jamming = 0.0; + info.speed = Main_GPS.speed; + info.timeUTC = Main_GPS.timeUTC; + //printf("MessageTelemetry: GpsInfo -> Send\n"); + SendMes(begin); +} + +extern Vec3 test_iner; + +//?????????? ??????? ????????? ??????????. ?????????? ??????? ? ???????, ????????? ????????? InertialInfo +void InertialInfo() +{ + //????? ???????? ? ?????? + HeaderBegin* begin; + PayloadInertialInfo& info = *(PayloadInertialInfo*)CreateMessageHeaders(begin, sizeof(PayloadInertialInfo), MESSAGES_ID::InertialInfo); + + info.x = test_iner.x; + info.y = test_iner.y; + info.z = test_iner.z; + info.baroAlt = DataORI.Bar.Alt; + info.pitch = DataORI.Pitch; + info.yaw = DataORI.Yaw; + info.roll = DataORI.Roll; + info.headingDeg = DataORI.Yaw; + info.speed = Main_GPS.speed; + info.pitchVel = 1.0; + info.yawVel = 1.0; + info.rollVel = 1.0; + //printf("MessageTelemetry: InertialInfo -> Send\n"); + SendMes(begin); +} +//????????? ????? ?? ??????? ?? ???????? ???????? ?????? +void CommandAck(PayloadCommandAck& ack) +{ + HeaderBegin* begin; + PayloadCommandAck& info = *(PayloadCommandAck*)CreateMessageHeaders(begin, sizeof(PayloadCommandAck), MESSAGES_ID::Ack); + info = ack; + //printf("MessageCommandACK: Send\n"); + SendMes(begin); +} +//?????????? ???????? ??????????? +static void ProcessingCommandLand() +{ + MainFlyMode=MAIN_FLY_MODE::STOP; + + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::Land; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ????????? ?????? (?????????) +static void ProcessingCommandPause() +{ + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::Pause; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ???????? ? ????? ?????? +static void ProcessingCommandGoHome() +{ + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::GoHome; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ??????????? ?????? +static void ProcessingCommandContinue() +{ + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::Continue; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ??????? ??????? +static void ProcessingCommandStartEngine() +{ + if(MainFlyMode!=MAIN_FLY_MODE::STOP) MainFlyMode=MAIN_FLY_MODE::START; + + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::StartEngine; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ????????? ??????? +static void ProcessingCommandStopEngine() +{ + MainFlyMode=MAIN_FLY_MODE::WAIT; + + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::StopEngine; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ????????? ???????? ?????? +static void ProcessingCommandChangeSpeed(PayloadCommandChangeSpeed* payload) +{ + // ????????? ???????... + //payload->speed; + + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::ChangeSpeed; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ????? ????????????? ??????? +static void ProcessingCommandChangeNav(PayloadCommandChangeNav* payload) +{ + PROT_Nav=(NAV_SYS_MODE)payload->nav_id; + // ????????? ???????... + //payload->nav_id; + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::ChangeNav; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); +} +//?????????? ???????? ??????????? ? ????? ?? ?????????? ??????????? +static void ProcessingCommandGoToGlobal(PayloadCommandGoToGlobal* payload) +{ + PointGPS.Latitude=payload->lat; + PointGPS.Longitude=payload->lon; + PointGPS.Altitude=payload->abs_alt; + + if(MainFlyMode!=MAIN_FLY_MODE::STOP) MainFlyMode=MAIN_FLY_MODE::FLY; + + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::GoToGlobal; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} +//?????????? ???????? ??????????? ? ????? ?? ????????? ??????????? +static void ProcessingCommandGoToLocal(PayloadCommandGoToLocal* payload) +{ + // ????????? ???????... + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::GoToLocal; + info.errorCode = ERROR_CODE_COMMAND::No_error; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + CommandAck(info); + +} + +// +static void ProcessingCommandSetParameter(PayloadCommandSetParameter* payload) +{ + unsigned char cat_id = payload->cat_id; // ID ????????? + unsigned char param_id = payload->param_id; // ID ????????? + DATA_TYPES param_type = payload->param_type_code; // ??? ?????? + unsigned char param_len = payload->param_len; // ?????? ??????? ?????? + //payload->param_data; // ?????? ???? ????????? + + PayloadCommandAck info; + info.commandId = COMMANDS_NAME::SetParameter; + info.status = FEASIBILITY_CODE_COMMAND::accepted; + info.errorCode = ERROR_CODE_COMMAND::No_error; + CommandAck(info); +} + +//????? ?????????? ????????? ? ???????? +static void ProcessingCommand(CommandObj* commandObject) { + switch (commandObject->commandId) + { + case COMMANDS_NAME::Land: ProcessingCommandLand(); return; + case COMMANDS_NAME::Pause: ProcessingCommandPause(); return; + case COMMANDS_NAME::GoHome: ProcessingCommandGoHome(); return; + case COMMANDS_NAME::Continue: ProcessingCommandContinue(); return; + case COMMANDS_NAME::StartEngine: ProcessingCommandStartEngine(); return; + case COMMANDS_NAME::StopEngine: ProcessingCommandStopEngine(); return; + case COMMANDS_NAME::ChangeSpeed: ProcessingCommandChangeSpeed((PayloadCommandChangeSpeed*)commandObject->data); return; + case COMMANDS_NAME::ChangeNav: ProcessingCommandChangeNav((PayloadCommandChangeNav*)commandObject->data); return; + case COMMANDS_NAME::GoToGlobal: ProcessingCommandGoToGlobal((PayloadCommandGoToGlobal*)commandObject->data); return; + case COMMANDS_NAME::GoToLocal: ProcessingCommandGoToLocal((PayloadCommandGoToLocal*)commandObject->data); return; + case COMMANDS_NAME::SetParameter: ProcessingCommandSetParameter((PayloadCommandSetParameter*)commandObject->data); return; + } +} +//?????????? ????????? ???????????? ????? +static void ConnectionTest() +{ + HeaderBegin* begin; + CreateMessageHeaders(begin, sizeof(PayloadBatteryInfo), MESSAGES_ID::ConnectionTest); + + begin->SetCRC(); + + UART2_Send(begin, sizeof(HeaderBegin) + begin->len1); +} +//?????????? ????????? ??????? ??????? ??????? +static void StatusCommand(PayloadStatusCommand* payload) +{ + // payload->commandId; ??? ?????? ???? ?????-?? ???????? ???????? ????????? ?????????? ??????? ?? ?? ID + HeaderBegin* begin; + PayloadStatusCommand& info = *(PayloadStatusCommand*)CreateMessageHeaders(begin, sizeof(PayloadStatusCommand), MESSAGES_ID::StatusCommand); + info.commandId = payload->commandId; + info.executionCode = EXEC_CODE_COMMAND::completed; + info.errorCode = ERROR_CODE_COMMAND::No_error; + SendMes(begin); +} + +static void CountMenuCategories() +{ + // + unsigned char count_categories = 4; + unsigned char categoriesNamesLen[4] = { 5, 6, 5, 7 }; + HeaderBegin* begin; + PayloadCountMenuCategories& info = *(PayloadCountMenuCategories*)CreateMessageHeaders(begin, sizeof(PayloadCountMenuCategories) + count_categories * sizeof(unsigned char), MESSAGES_ID::CountMenuCategories); + + info.countCategories = count_categories; + for (int i = 0; i < info.countCategories; i++) { + info.data[i] = categoriesNamesLen[i]; + } + //printf("MessageTelemetry: SysInfo -> Send\n"); + SendMes(begin); +} + +static void MenuCategories(PayloadMenuCategories* payload) +{ + const char* names[4] = { "Main1","PID_S1","MOTOR", "ACCELER"}; // ????? ????????? + unsigned char categoriesNamesLen[4] = { 5, 6, 5, 7 }; // ????? ???? ????????? (????? ? ????????? utf-8) + unsigned char req_count = payload->countCategories; + unsigned char total_len_names = 0; + for (int i = 0; i < req_count; i++) + { + unsigned char cat_id = (payload->categories)[i]; + unsigned char cat_name_len = categoriesNamesLen[(payload->categories)[i]]; + total_len_names += cat_name_len; + } + HeaderBegin* begin; + PayloadMenuCategories& info = *(PayloadMenuCategories*)CreateMessageHeaders(begin, sizeof(PayloadMenuCategories) + req_count * sizeof(MenuCategori) + total_len_names * sizeof(unsigned char), MESSAGES_ID::CategoriesMenu); + info.countCategories = req_count; + MenuCategori* menu = (MenuCategori*)info.categories; + for (int i = 0; i < req_count; i++) + { + menu->id = (payload->categories)[i]; + menu->count_param = 1; + menu->len_name = categoriesNamesLen[menu->id]; + memcpy(menu->name, names[menu->id], menu->len_name); + menu = (MenuCategori*)(((char*)menu) + sizeof(MenuCategori) + menu->len_name); + } + SendMes(begin); +} + +static void CategoriesParameters(PayloadCategoriesParameters* payload) +{ + unsigned char cat_id = payload->cat_id; // id ????????? ??? ?????? ????????? + unsigned char param_id = payload->param_id; // id ????????? ??? ?????? ????????? + // ????????? ????????? + const char* name = "PARAMETER1"; + unsigned char len_name = 10; + float param1 = 0.231; + DATA_TYPES param_type = DATA_TYPES::dt_float_32; + // + + HeaderBegin* begin; + PayloadCategoriesParameters& info = *(PayloadCategoriesParameters*)CreateMessageHeaders(begin, sizeof(PayloadCategoriesParameters) + len_name + sizeof(param1), MESSAGES_ID::CategoriesParameters); + info.cat_id = cat_id; + info.param_id = param_id; + info.param_name_len = len_name; + info.param_len = sizeof(param1); + info.param_type_code = param_type; + memcpy(info.param_data, name, len_name); + memcpy(&info.param_data[len_name], ¶m1, sizeof(param1)); + SendMes(begin); +} + +//void Ping(HeaderMessages* message) +//{ +// HeaderBegin* begin; +// CreateMessageHeaders(begin, sizeof(PayloadBatteryInfo), MESSAGES_ID::Ping); +// //--- +// SendMes(begin); +// //--- +// printf("Ping %d Pong %d \n", message->timeusec, ((HeaderMessages*)begin->data)->timeusec); +//} +// +//void Pong(HeaderMessages* message) +//{ +// HeaderBegin* begin; +// CreateMessageHeaders(begin, sizeof(PayloadBatteryInfo), MESSAGES_ID::Pong); +// //--- +// SendMes(begin); +// //--- +// printf("Pong %d Ping %d \n", message->timeusec, ((HeaderMessages*)begin->data)->timeusec); +//} + +static void ProcessingMessage(HeaderMessages* message) +{ + switch (message->msgId) + { + /*case MESSAGES_ID::Ping: Pong(message); return; + case MESSAGES_ID::Pong: Ping(message); return;*/ + case MESSAGES_ID::BatteryInfo: BatteryInfo(); return; + case MESSAGES_ID::GyroInfo: GyroInfo(); return; + case MESSAGES_ID::AccelInfo: AccelInfo(); return; + case MESSAGES_ID::GpsInfo: GpsInfo(); return; + case MESSAGES_ID::InertialInfo: InertialInfo(); return; + case MESSAGES_ID::SysInfo: SysInfo(); return; + case MESSAGES_ID::Command: ProcessingCommand((CommandObj*)message->data); return; + case MESSAGES_ID::ConnectionTest: ConnectionTest(); return; + case MESSAGES_ID::StatusCommand: StatusCommand((PayloadStatusCommand*)message->data); return; + + case MESSAGES_ID::CountMenuCategories: CountMenuCategories(); return; + case MESSAGES_ID::CategoriesMenu: MenuCategories((PayloadMenuCategories*)message->data); return; + case MESSAGES_ID::CategoriesParameters: CategoriesParameters((PayloadCategoriesParameters*)message->data); return; + } +} + +//void TestPing() +//{ +// HeaderMessages message; +// message.timeusec = GetTickCount(); +// Pong(&message); +//} + +void PROT_Update() +{ + char byte; + unsigned char size = UART2_Recv(&byte, 1); + if (size) MainUpdate(byte); +} diff --git a/utils/prot.h b/utils/prot.h new file mode 100644 index 0000000..6f2ccf9 --- /dev/null +++ b/utils/prot.h @@ -0,0 +1,14 @@ +#pragma once + +#include "prot_head.h" + +extern Point PointGPS; + +enum class MAIN_FLY_MODE { WAIT, START, FLY, STOP }; + +extern MAIN_FLY_MODE MainFlyMode; + +extern STATUS_MODE Main_StatusMode; +extern SYS_MODE Main_SysMode; + +void PROT_Update(); diff --git a/utils/prot_head.h b/utils/prot_head.h new file mode 100644 index 0000000..9d7b142 --- /dev/null +++ b/utils/prot_head.h @@ -0,0 +1,318 @@ +#pragma once + +enum class MESSAGES_ID : unsigned char +{ + SysInfo = 1, + GyroInfo = 2, + AccelInfo = 3, + GpsInfo = 4, + InertialInfo = 5, + BatteryInfo = 6, + Ack = 7, + StatusCommand = 8, + StatusAllCommands = 9, + Command = 10, + RequestReg = 11, + ResponseReg = 12, + Auth = 13, + OpenKey = 14, + MissionCount = 15, + MissionItem = 16, + MissionItemAck = 17, + MissionRequestItem = 18, + RequestLastMessage = 19, + ConnectionTest = 20, + + CountMenuCategories = 32, + CategoriesMenu = 33, + CategoriesParameters = 34, + + //Ping = 200, // :) + //Pong = 201, // :] +}; +enum class COMMANDS_NAME : unsigned char +{ + ChangeNav = 1, + ChangeSpeed = 2, + Land = 3, + GoHome = 4, + StopEngine = 5, + StartEngine = 6, + Pause = 7, + Continue = 8, + GoToGlobal = 9, + GoToLocal = 10, + + SetParameter = 15, +}; +enum class ERROR_CODE_COMMAND : unsigned char +{ + No_error = 0, + Speed_has_already_been_set = 1, + Engines_are_already_running = 2, + Engines_have_already_been_stopped = 3, + UAV_is_already_on_the_ground = 4, + UAV_is_already_landing = 5, + UAV_is_already_moving = 6, + Mission_has_not_been_launched = 7, + Mission_is_already_on_pause = 8, + Mission_was_not_on_pause = 9, + Mission_was_not_launched = 10, + This_NavSys_has_already_been_applied = 11, + Lost_connection_with_controller = 12, + The_command_is_canceled_when_a_new_one_is_received = 13, + Error_reading_the_mission_file = 14, + Error_validating_the_mission_file = 15 +}; +enum class ENGINE_STATUS : unsigned char +{ + disable = 0, + enable = 1 +}; + +enum class STATUS_MODE : unsigned char +{ + on_ground = 1, + taking_off = 2, + fly = 3, + landing = 4 +}; + +enum class SYS_MODE : unsigned char +{ + take_off = 1, + land = 2, + go_home = 3, + auto_mode = 4, + hold = 5 +}; + +enum class NAV_SYS_MODE : unsigned char +{ + inertial = 1, + gps = 2, + Optical_flow = 3 +}; + +enum class EXEC_CODE_COMMAND : unsigned char +{ + error = 0, + in_progress = 1, + completed = 2 +}; + +enum class FEASIBILITY_CODE_COMMAND : unsigned char +{ + cannot_be_performed = 0, + accepted = 1 +}; + +enum class DATA_TYPES : unsigned char +{ + dt_char = 0, + dt_unsigned_char = 1, + dt_string = 2, + dt_short = 3, + dt_bool = 4, + dt_unsigned_short = 5, + dt_int = 6, + dt_unsigned_int = 7, + dt_long = 8, + dt_unsigned_long = 9, + dt_long_long = 10, + dt_unsigned_long_long = 11, + dt_float_32 = 12, + dt_float_64 = 13, + dt_unknown = 255 +}; + +#pragma pack(push,1) + +const unsigned short MaxLength = 256; +const unsigned char Global_stx = 0xAA; +//?????? ????????? +struct HeaderBegin +{ + unsigned char stx; + unsigned short len1; //Len header + payload (message) + unsigned short len2; //Len header + payload (message) + unsigned char crc; // CRC MESSAGE + unsigned char data[0]; // Message + //--- + bool CheckCRC(); + void SetCRC(); +}; +// ????????? ????????? +struct HeaderMessages +{ + MESSAGES_ID msgId; + unsigned char srcId; + unsigned char dstId; + unsigned char len; + unsigned long long timeusec; + unsigned char data[0]; +}; +struct CommandObj +{ + COMMANDS_NAME commandId; + unsigned char data[0]; +}; +//???????? ???????? ????????? ? ??????? ?? ??? +struct PayloadBatteryInfo +{ + unsigned char perCharge; + float voltage; + float amperage; + float temp; + float totalPower; + unsigned long long timeRemaining; +}; +// ????????? ? ??????? ?? ??????? ?????? +struct EnginePowerInfo +{ + unsigned char power; //??????? ???????? ?? ????? ?? 0 ?? 100% + unsigned int engineSpeed;//??????? ?????? ? ??????? ?????? + float current; // ??? ???????????? ??????? + float voltage; // ?????????? ?? ?????? + float temp; // ??????????? ?????? + +}; +struct PayloadSysInfo // ???????? ???????? ? ??????? ? ???????? ???? +{ + SYS_MODE mode; //??????? ????? ?????? (????? - 1, ??????? - 2, ????? ??????????????? ???????? ????? - 3, ????? ??????????? ?????? - 4, ???????? - 5) + STATUS_MODE statusMode; //??????? ?????? ????? (?? ????? (on ground) - 1, ????? ?????? (TakingOff) - 2, ????? (In air) - 3, ??????????? (Landing) - 4) + NAV_SYS_MODE navSys; // ??????? ???????????? ??????? ????????? (GPS\???\Optical Flow) ??? - 1, GPS - 2, Optical Flow - 3 + ENGINE_STATUS engineStatus; // ??????? ????????? ???????. ???? - 0, ??? - 1. + unsigned char engineCount; // ?????????? ?????????? ?? ???? + float pressureBaro; //??????????? ???????? + float tempBaro; // ??????????? ???. ????? + EnginePowerInfo enginePower[0]; +}; +struct PayloadGyroInfo // ???????? ???????? ? ??????? ?? ????????? +{ + float yawGyroVel; // ??????? ???????? ????????? ???? ???????? (? ??? ????? ??????????? ???\??) + float pitchGyroVel; // ??????? ???????? ????????? ???? ??????? (? ??? ????? ??????????? ???\??) + float rollGyroVel; // ??????? ???????? ????????? ???? ????? (? ??? ????? ??????????? ???\??) +}; +struct PayloadAccelInfo // ???????? ???????? ????????? ? ??????? ?? ????????????? +{ + float yawAccelVel; // ??????? ????????? ????????? ???? ???????? (Z) + float pitchAccelVel; // ??????? ????????? ????????? ???? ??????? (Y) + float rollAccelVel; // ??????? ????????? ????????? ???? ????? (X) + float aX; // ????????? ?? X (?\?^2) + float aY; // ????????? ?? ? (?\?^2) + float aZ; // ????????? ?? Z (?\?^2) + float tempAccel; //??????????? ????????????? +}; +struct PayloadGpsInfo // ???????? ???????? ????????? ? ??????? ?? GPS ??????? +{ + float lat; // + float lon; // + float absAlt; // + float realAlt; // + float hdop; // + float vdop; // + float pdop; // + float noise; // + float jamming; // + unsigned char satVisible; + unsigned char satUsed; // + float speed; // + unsigned char fixType; // NO_GPS - 0, NO_FIX - 1, 2D_FIX - 2, 3D_FIX - 3, DGPS - 4, RTK_FLOAT - 5, RTK_FIXED - 6, STATIC - 7, PPP - 8 + unsigned long long timeUTC; // UTC - GPS +}; +struct PayloadInertialInfo // ???????? ???????? ? ??????? ?? ???????????? ??????? ????????? +{ + float x; // ?????????? X (?? ????????? ??????? ?????????) + float y; // ?????????? Y (?? ????????? ??????? ?????????) + float z; // ?????????? ?????? (?? ????????? ??????? ?????????) + float headingDeg; // ??????? ??????????? ???????? ???? ???????????? ?????? + float speed; // ???????? ???? (?????????? ?? ?? GPS) + float roll; // ??????? ???? ????? ? ???????? + float pitch; // ??????? ???? ??????? ? ???????? + float yaw; // ??????? ???? ???????? ? ???????? + float rollVel; // ???????? ?? ??????????? ????? ?\? (? ??????????? ??? Y) + float pitchVel; // ???????? ?? ??????????? ??????? ?\? (? ??????????? ??? ?) + float yawVel; // ???????? ?? ??????????? ???????? ?\? (? ??????????? ??? Z) + float baroAlt; // ?????? ? ?????? ?? ????????? +}; +//???????? ???????? ????????? ? ??????? ? ????????? ??????? +struct PayloadCommandAck +{ + COMMANDS_NAME commandId; + FEASIBILITY_CODE_COMMAND status; // 0 - ?? ????? ???? ????????? (??????????? ??? ??????), 1 - ??????? + ERROR_CODE_COMMAND errorCode; +}; +struct PayloadStatusCommand +{ + COMMANDS_NAME commandId; + EXEC_CODE_COMMAND executionCode; // 0 - ?????? ??? ?????????? ,1 - ??????????? ,2 - ????????? ???????. + ERROR_CODE_COMMAND errorCode; +}; +// ???????? ???????? ??????? ??? ????? ???????? ?????? +struct PayloadCommandChangeSpeed +{ + float speed; +}; +// ???????? ???????? ??????? ??? ????? ??????? ???. ???. ???????. +struct PayloadCommandChangeNav +{ + unsigned char nav_id; // Inertial - 1, GPS = 2, Oprical_Flow = 3 +}; +// ???????? ???????? ??????? ??? ??????????? ? ????? ?? ?????????? ??????????? +struct PayloadCommandGoToGlobal +{ + float lat; + float lon; + float abs_alt; + float speed; +}; +// ???????? ???????? ??????? ??? ??????????? ? ????? ?? ????????? ??????????? +struct PayloadCommandGoToLocal +{ + float x; + float y; + float z; + float speed; +}; + +struct PayloadCountMenuCategories +{ + unsigned char countCategories; + unsigned char data[0]; +}; + +struct MenuCategori +{ + unsigned char id; + unsigned char len_name; + unsigned char count_param; + char name[0]; +}; + +struct PayloadMenuCategories +{ + unsigned char countCategories; + unsigned char categories[0]; +}; + +struct PayloadCategoriesParameters +{ + unsigned char cat_id; + unsigned char param_id; + unsigned char param_name_len; + unsigned char param_len; + DATA_TYPES param_type_code; + char param_data[0]; +}; + +struct PayloadCommandSetParameter +{ + unsigned char cat_id; + unsigned char param_id; + DATA_TYPES param_type_code; + unsigned char param_len; + char param_data[0]; +}; + +#pragma pack(pop) diff --git a/utils/quat.cpp b/utils/quat.cpp new file mode 100644 index 0000000..7700351 --- /dev/null +++ b/utils/quat.cpp @@ -0,0 +1,275 @@ +#include "quat.h" +#include + +static const float PI = 3.14159265359f; +static const float TO_DEG = 180.0f/PI; +static const float TO_RAD = PI/180.0f; + +struct Quaternion +{ + float w, x, y, z; +}; + +static Quaternion qCurrent = { 1, 0, 0, 0 }; + +static const float period = 0.01f; // 100Hz + +static bool isFirst = true; + +inline void vecNormalize(Vec3& v) +{ + float n = sqrtf(v.x * v.x + v.y * v.y + v.z * v.z); + if (n > 1e-9f) + { + v.x /= n; + v.y /= n; + v.z /= n; + } +} + +inline Vec3 vecCross(const Vec3& a, const Vec3& b) +{ + return + { + a.y * b.z - a.z * b.y, + a.z * b.x - a.x * b.z, + a.x * b.y - a.y * b.x + }; +} + +inline void normalizeQuaternion(Quaternion& q) +{ + float norm = sqrtf(q.w * q.w + q.x * q.x + q.y * q.y + q.z * q.z); + if (norm > 1e-12f) + { + q.w /= norm; + q.x /= norm; + q.y /= norm; + q.z /= norm; + } +} + +static Quaternion quaternionMultiply(const Quaternion& q1, const Quaternion& q2) +{ + Quaternion r; + r.w = q1.w * q2.w - q1.x * q2.x - q1.y * q2.y - q1.z * q2.z; + r.x = q1.w * q2.x + q1.x * q2.w + q1.y * q2.z - q1.z * q2.y; + r.y = q1.w * q2.y - q1.x * q2.z + q1.y * q2.w + q1.z * q2.x; + r.z = q1.w * q2.z + q1.x * q2.y - q1.y * q2.x + q1.z * q2.w; + return r; +} + +static Quaternion rotateVectorByQuaternion(const Quaternion& q, const Vec3& In) +{ + Quaternion r = quaternionMultiply(quaternionMultiply(q, Quaternion{ 0, In.x, In.y, In.z }), Quaternion{ q.w, -q.x, -q.y, -q.z }); + + return r; +} + +static Vec3 backRotateVectorByQuaternion(const Quaternion& q, const Vec3& In) +{ + Quaternion r = quaternionMultiply(quaternionMultiply(Quaternion{q.w, -q.x, -q.y, -q.z}, Quaternion{ 0, In.x, In.y, In.z }), q); + + return { r.x, r.y, r.z }; +} + +static Quaternion backRotateVectorByQuaternion2(const Quaternion& q, const Quaternion& In) +{ + Quaternion r = quaternionMultiply(quaternionMultiply(Quaternion{q.w, -q.x, -q.y, -q.z}, In), q); + + return r; +} + +static Quaternion createYawQuaternion(float angle) +{ + Quaternion q; + + q.w = cosf(angle); + q.x = 0.0f; + q.y = 0.0f; + q.z = sinf(angle); + + return q; +} + +static Quaternion AccQuaternion(Quaternion& current, Vec3 a, float gravity, Vec3 xyz, float& error) +{ + float acc = sqrtf(a.x*a.x+a.y*a.y+a.z*a.z); + if(acc>(1.0f+gravity) || acc<(1.0f-gravity)) return current; + + vecNormalize(a); + + float x=a.x-xyz.x, y=a.y-xyz.y, z=a.z-xyz.z; + + error=sqrtf(x*x+y*y+z*z)/10.0f; + + Vec3 g { 0, 0, 1 }; + Vec3 axis = vecCross(g, a); + float w = 1 + (g.x * a.x + g.y * a.y + g.z * a.z); + Quaternion q = { w, axis.x, axis.y, axis.z }; + normalizeQuaternion(q); + + Quaternion qYaw {current.w, 0, 0, current.z}; + + return quaternionMultiply(q, qYaw); // ??????????? ?????? ?? Z +} + +static Quaternion GyroQuaternion(Quaternion& current, float wx, float wy, float wz) +{ + Quaternion Mapp = current; + Quaternion Spd { 0, wx, wy, wz }; + Quaternion aq = quaternionMultiply(Spd, Mapp); + + Mapp.w -= 0.5f * aq.w; + Mapp.x -= 0.5f * aq.x; + Mapp.y -= 0.5f * aq.y; + Mapp.z -= 0.5f * aq.z; + + normalizeQuaternion(Mapp); + return Mapp; +} + +static Quaternion nlerp(const Quaternion& q1, const Quaternion& q2, float alpha) +{ + + float dot = q1.w * q2.w + q1.x * q2.x + q1.y * q2.y + q1.z * q2.z; + + Quaternion q2_ = q2; + if (dot < 0) + { + q2_.w = -q2.w; + q2_.x = -q2.x; + q2_.y = -q2.y; + q2_.z = -q2.z; + } + + Quaternion r; + r.w = (1.0f - alpha) * q1.w + alpha * q2_.w; + r.x = (1.0f - alpha) * q1.x + alpha * q2_.x; + r.y = (1.0f - alpha) * q1.y + alpha * q2_.y; + r.z = (1.0f - alpha) * q1.z + alpha * q2_.z; + + normalizeQuaternion(r); + + return r; +} + +inline float GetAngle(float a1, float a2, float az) +{ + if(a2 == 0.0f && az == 0.0f) + { + if(a1>0.0f) return 90.0f; + if(a1<0.0f) return -90.0f; + return 0.0f; + } + + return atanf(a1/sqrtf(a2*a2+az*az)) * TO_DEG; +} + +static Vec3 quaternionToPitchRollYaw(const Quaternion& q, Vec3& cosXYZ) +{ + Quaternion pry=rotateVectorByQuaternion(q, {0, 0, 1}); + + float yaw = 2.0f * atan2f(q.z, q.w) * TO_DEG; + if(yaw<0.0f) yaw=360.0f+yaw; + + cosXYZ = {pry.x, pry.y, pry.z}; + + return // Sovereign orientation + { + GetAngle(pry.y, pry.x, pry.z), // Pitch + GetAngle(-pry.x, pry.y, pry.z), // Roll + yaw // Yaw + }; +} + +static void addMagneto(Quaternion& q, Vec3 mag, float alpha, const float shift) +{ + static Quaternion yq = createYawQuaternion(shift*TO_RAD); + + vecNormalize(mag); + + Quaternion mQ={0, mag.x, mag.y, mag.z}; + + Quaternion mW = backRotateVectorByQuaternion2(q, mQ); + + mW=quaternionMultiply(mW, yq); // Shifting the axes to the true north + + float gamma = mW.x * mW.x + mW.y * mW.y; + float beta = sqrtf(gamma + mW.x * sqrtf(gamma)); + + Quaternion mD + { + beta / (sqrtf(2.0f * gamma)), + 0.0f, + 0.0f, + mW.y / (sqrtf(2.0f) * beta), + }; + + mD.w = (1.0f - alpha) + alpha * mD.w; + mD.z = alpha * mD.z; + + if(mD.w!=mD.w || mD.x!=mD.x || mD.y!=mD.y || mD.z!=mD.z) return; + + q=quaternionMultiply(q, mD); + normalizeQuaternion(q); +} + +ORI WorkAccGyroMag(const Vec3 acc, const Vec3 gyr, const Vec3 mag, const float mag_shift, const float alpha) +{ + float wx = gyr.x * 500.0f / 30000.0f * TO_RAD * period; + float wy = gyr.y * 500.0f / 30000.0f * TO_RAD * period; + float wz = gyr.z * 500.0f / 30000.0f * TO_RAD * period; + + Vec3 aB = acc; + + Vec3 cosXYZ; + Vec3 pry=quaternionToPitchRollYaw(qCurrent, cosXYZ); + + static float error=0; + // Quaternion qAcc = AccQuaternion(qCurrent, aB, 0.05f, cosXYZ, error); // Tolerance for gravity deviation 5% + + qCurrent = GyroQuaternion(qCurrent, wx, wy, wz); + + if(error>0.01f) error=0.01f; + if(error