├── .cproject
├── .gitignore
├── .mxproject
├── .project
├── BoardConfig
└── board_config.h
├── Calibration
├── calibration.cpp
└── calibration.hpp
├── Core
├── Inc
│ ├── adc.h
│ ├── crc.h
│ ├── dma.h
│ ├── gpio.h
│ ├── jdrive_main.hpp
│ ├── main.h
│ ├── spi.h
│ ├── stm32f4xx_hal_conf.h
│ ├── stm32f4xx_it.h
│ ├── tim.h
│ └── usart.h
├── Src
│ ├── adc.c
│ ├── crc.c
│ ├── dma.c
│ ├── gpio.c
│ ├── jdrive_main.cpp
│ ├── main.c
│ ├── spi.c
│ ├── stm32f4xx_hal_msp.c
│ ├── stm32f4xx_it.c
│ ├── syscalls.c
│ ├── sysmem.c
│ ├── system_stm32f4xx.c
│ ├── tim.c
│ └── usart.c
└── Startup
│ └── startup_stm32f446retx.s
├── DigitalFilter
├── lowpass.cpp
└── lowpass.hpp
├── Drivers
├── CMSIS
│ ├── Device
│ │ └── ST
│ │ │ └── STM32F4xx
│ │ │ └── Include
│ │ │ ├── stm32f446xx.h
│ │ │ ├── stm32f4xx.h
│ │ │ └── system_stm32f4xx.h
│ └── Include
│ │ ├── cmsis_armcc.h
│ │ ├── cmsis_armclang.h
│ │ ├── cmsis_compiler.h
│ │ ├── cmsis_gcc.h
│ │ ├── cmsis_iccarm.h
│ │ ├── cmsis_version.h
│ │ ├── core_armv8mbl.h
│ │ ├── core_armv8mml.h
│ │ ├── core_cm0.h
│ │ ├── core_cm0plus.h
│ │ ├── core_cm1.h
│ │ ├── core_cm23.h
│ │ ├── core_cm3.h
│ │ ├── core_cm33.h
│ │ ├── core_cm4.h
│ │ ├── core_cm7.h
│ │ ├── core_sc000.h
│ │ ├── core_sc300.h
│ │ ├── mpu_armv7.h
│ │ ├── mpu_armv8.h
│ │ └── tz_context.h
└── STM32F4xx_HAL_Driver
│ ├── Inc
│ ├── Legacy
│ │ └── stm32_hal_legacy.h
│ ├── stm32f4xx_hal.h
│ ├── stm32f4xx_hal_adc.h
│ ├── stm32f4xx_hal_adc_ex.h
│ ├── stm32f4xx_hal_cortex.h
│ ├── stm32f4xx_hal_crc.h
│ ├── stm32f4xx_hal_def.h
│ ├── stm32f4xx_hal_dma.h
│ ├── stm32f4xx_hal_dma_ex.h
│ ├── stm32f4xx_hal_exti.h
│ ├── stm32f4xx_hal_flash.h
│ ├── stm32f4xx_hal_flash_ex.h
│ ├── stm32f4xx_hal_flash_ramfunc.h
│ ├── stm32f4xx_hal_gpio.h
│ ├── stm32f4xx_hal_gpio_ex.h
│ ├── stm32f4xx_hal_pwr.h
│ ├── stm32f4xx_hal_pwr_ex.h
│ ├── stm32f4xx_hal_rcc.h
│ ├── stm32f4xx_hal_rcc_ex.h
│ ├── stm32f4xx_hal_spi.h
│ ├── stm32f4xx_hal_tim.h
│ ├── stm32f4xx_hal_tim_ex.h
│ └── stm32f4xx_hal_uart.h
│ └── Src
│ ├── stm32f4xx_hal.c
│ ├── stm32f4xx_hal_adc.c
│ ├── stm32f4xx_hal_adc_ex.c
│ ├── stm32f4xx_hal_cortex.c
│ ├── stm32f4xx_hal_crc.c
│ ├── stm32f4xx_hal_dma.c
│ ├── stm32f4xx_hal_dma_ex.c
│ ├── stm32f4xx_hal_exti.c
│ ├── stm32f4xx_hal_flash.c
│ ├── stm32f4xx_hal_flash_ex.c
│ ├── stm32f4xx_hal_flash_ramfunc.c
│ ├── stm32f4xx_hal_gpio.c
│ ├── stm32f4xx_hal_pwr.c
│ ├── stm32f4xx_hal_pwr_ex.c
│ ├── stm32f4xx_hal_rcc.c
│ ├── stm32f4xx_hal_rcc_ex.c
│ ├── stm32f4xx_hal_spi.c
│ ├── stm32f4xx_hal_tim.c
│ ├── stm32f4xx_hal_tim_ex.c
│ └── stm32f4xx_hal_uart.c
├── Encoder
├── AS5047.cpp
└── AS5047.hpp
├── ErrorControl
└── errorControl.hpp
├── FastMath
├── fast_math.cpp
└── fast_math.hpp
├── Images
└── PCB_Image.png
├── J-Drive.ioc
├── LICENSE
├── Lowlevel
├── lowlevel.cpp
└── lowlevel.hpp
├── MotorControl
├── motor_control.cpp
└── motor_control.hpp
├── Protection
├── protection.cpp
└── protection.hpp
├── Protocol
├── controlTable.cpp
├── controlTable.hpp
├── fifo.cpp
├── fifo.hpp
├── protocol.cpp
└── protocol.hpp
├── README.md
├── STM32F446RETX_FLASH.ld
├── STM32F446RETX_RAM.ld
└── Util
├── util.cpp
└── util.hpp
/.gitignore:
--------------------------------------------------------------------------------
1 | # Prerequisites
2 | *.d
3 |
4 | # Compiled Object files
5 | *.slo
6 | *.lo
7 | *.o
8 | *.obj
9 |
10 | # Precompiled Headers
11 | *.gch
12 | *.pch
13 |
14 | # Compiled Dynamic libraries
15 | *.so
16 | *.dylib
17 | *.dll
18 |
19 | # Fortran module files
20 | *.mod
21 | *.smod
22 |
23 | # Compiled Static libraries
24 | *.lai
25 | *.la
26 | *.a
27 | *.lib
28 |
29 | # Executables
30 | *.exe
31 | *.out
32 | *.app
33 |
34 | .settings
35 | J-Drive Debug.launch
36 | Debug/
37 |
38 |
--------------------------------------------------------------------------------
/.mxproject:
--------------------------------------------------------------------------------
1 | [PreviousLibFiles]
2 | LibFiles=Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h;Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h;Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f446xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;Drivers/CMSIS/Include/cmsis_armcc.h;Drivers/CMSIS/Include/cmsis_armclang.h;Drivers/CMSIS/Include/cmsis_compiler.h;Drivers/CMSIS/Include/cmsis_gcc.h;Drivers/CMSIS/Include/cmsis_iccarm.h;Drivers/CMSIS/Include/cmsis_version.h;Drivers/CMSIS/Include/core_armv8mbl.h;Drivers/CMSIS/Include/core_armv8mml.h;Drivers/CMSIS/Include/core_cm0.h;Drivers/CMSIS/Include/core_cm0plus.h;Drivers/CMSIS/Include/core_cm1.h;Drivers/CMSIS/Include/core_cm23.h;Drivers/CMSIS/Include/core_cm3.h;Drivers/CMSIS/Include/core_cm33.h;Drivers/CMSIS/Include/core_cm4.h;Drivers/CMSIS/Include/core_cm7.h;Drivers/CMSIS/Include/core_sc000.h;Drivers/CMSIS/Include/core_sc300.h;Drivers/CMSIS/Include/mpu_armv7.h;Drivers/CMSIS/Include/mpu_armv8.h;Drivers/CMSIS/Include/tz_context.h;
3 |
4 | [PreviousUsedCubeIDEFiles]
5 | SourceFiles=Core\Src\main.c;Core\Src\gpio.c;Core\Src\adc.c;Core\Src\crc.c;Core\Src\dma.c;Core\Src\spi.c;Core\Src\tim.c;Core\Src\usart.c;Core\Src\stm32f4xx_it.c;Core\Src\stm32f4xx_hal_msp.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Core\Src/system_stm32f4xx.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_exti.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_spi.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c;Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_uart.c;Core\Src/system_stm32f4xx.c;Drivers/CMSIS/Device/ST/STM32F4xx/Source/Templates/system_stm32f4xx.c;;
6 | HeaderPath=Drivers\STM32F4xx_HAL_Driver\Inc;Drivers\STM32F4xx_HAL_Driver\Inc\Legacy;Drivers\CMSIS\Device\ST\STM32F4xx\Include;Drivers\CMSIS\Include;Core\Inc;
7 | CDefines=USE_HAL_DRIVER;STM32F446xx;USE_HAL_DRIVER;USE_HAL_DRIVER;
8 |
9 | [PreviousGenFiles]
10 | AdvancedFolderStructure=true
11 | HeaderFileListSize=10
12 | HeaderFiles#0=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/gpio.h
13 | HeaderFiles#1=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/adc.h
14 | HeaderFiles#2=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/crc.h
15 | HeaderFiles#3=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/dma.h
16 | HeaderFiles#4=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/spi.h
17 | HeaderFiles#5=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/tim.h
18 | HeaderFiles#6=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/usart.h
19 | HeaderFiles#7=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/stm32f4xx_it.h
20 | HeaderFiles#8=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/stm32f4xx_hal_conf.h
21 | HeaderFiles#9=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc/main.h
22 | HeaderFolderListSize=1
23 | HeaderPath#0=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Inc
24 | HeaderFiles=;
25 | SourceFileListSize=10
26 | SourceFiles#0=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/gpio.c
27 | SourceFiles#1=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/adc.c
28 | SourceFiles#2=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/crc.c
29 | SourceFiles#3=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/dma.c
30 | SourceFiles#4=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/spi.c
31 | SourceFiles#5=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/tim.c
32 | SourceFiles#6=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/usart.c
33 | SourceFiles#7=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/stm32f4xx_it.c
34 | SourceFiles#8=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/stm32f4xx_hal_msp.c
35 | SourceFiles#9=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src/main.c
36 | SourceFolderListSize=1
37 | SourcePath#0=C:/Users/JiuKim/Desktop/STM32/J-Drive/Core/Src
38 | SourceFiles=;
39 |
40 |
--------------------------------------------------------------------------------
/.project:
--------------------------------------------------------------------------------
1 |
2 |
3 | J-Drive
4 |
5 |
6 |
7 |
8 |
9 | org.eclipse.cdt.managedbuilder.core.genmakebuilder
10 | clean,full,incremental,
11 |
12 |
13 |
14 |
15 | org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
16 | full,incremental,
17 |
18 |
19 |
20 |
21 |
22 | com.st.stm32cube.ide.mcu.MCUProjectNature
23 | com.st.stm32cube.ide.mcu.MCUCubeProjectNature
24 | org.eclipse.cdt.core.cnature
25 | org.eclipse.cdt.core.ccnature
26 | com.st.stm32cube.ide.mcu.MCUCubeIdeServicesRevAev2ProjectNature
27 | com.st.stm32cube.ide.mcu.MCUAdvancedStructureProjectNature
28 | com.st.stm32cube.ide.mcu.MCUEndUserDisabledTrustZoneProjectNature
29 | com.st.stm32cube.ide.mcu.MCUSingleCpuProjectNature
30 | com.st.stm32cube.ide.mcu.MCURootProjectNature
31 | org.eclipse.cdt.managedbuilder.core.managedBuildNature
32 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
33 |
34 |
35 |
--------------------------------------------------------------------------------
/BoardConfig/board_config.h:
--------------------------------------------------------------------------------
1 | #ifndef BOARD_CONFIG_H_
2 | #define BOARD_CONFIG_H_
3 |
4 | #define HW_VER_MAJOR 1
5 | #define HW_VER_MINOR 0
6 |
7 | #define FW_VER_MAJOR 1
8 | #define FW_VER_MINOR 0
9 |
10 | #define MODEL_NUMBER 54025
11 |
12 | #define ONBOARD_TEMP_COEFF 299e-4f
13 | #define DC_VOLTAGE_COEFF 756e-5f
14 |
15 | #define DELTA_T 0.000044425f
16 |
17 | #define SUPPLY_PROTECTION 2.0f
18 |
19 | #define FAST_MATH_TABLE_SIZE 0x1FFF
20 |
21 | #define ACCEKERATION_FILTER_CUTOFF_FREQ 10.0f
22 | #define VELOCITY_FILTER_CUTOFF_FREQ 5.0f
23 | #define POSITION_FILTER_CUTOFF_FREQ 100.0f
24 | #define CURRENT_FILTER_CUTOFF_FREQ 100.0f
25 |
26 | #define UART_FIFO_BUFFER_SIZE 0xFFF
27 |
28 | #define CONTROLTABLE_END_ADDRESS 51
29 | #define CONTROLTABLE_EEPROM_END_ADDRESS 27
30 |
31 | #endif
32 |
--------------------------------------------------------------------------------
/Calibration/calibration.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | void Calibration::Init()
4 | {
5 | done = 0;
6 | startUpCounter = 0;
7 | avgCounter = 0;
8 | EncoderCalibration = 0;
9 | encoderOffset = 0.0f;
10 | ADC1Offset = 0;
11 | ADC2Offset = 0;
12 | }
13 |
14 | void Calibration::SetControlTable(ControlTable *_controlTable)
15 | {
16 | controlTable = _controlTable;
17 | }
18 |
19 | void Calibration::CalibrationUpdate()
20 | {
21 | if (!done)
22 | {
23 | if (EncoderCalibration)
24 | {
25 | float a, b, c;
26 |
27 | DQZTransInv(Limiter(*(float*)&controlTable->controlTableData[51].data, 0.9f), 0.0f, 0.0f, &a, &b, &c);
28 |
29 | a = a + 0.5f;
30 | b = b + 0.5f;
31 | c = c + 0.5f;
32 |
33 | uint16_t aDuty = (uint16_t) (a * ((float) (0xFFF)));
34 | uint16_t bDuty = (uint16_t) (b * ((float) (0xFFF)));
35 | uint16_t cDuty = (uint16_t) (c * ((float) (0xFFF)));
36 |
37 | SetInverterPWMDuty(aDuty, bDuty, cDuty);
38 |
39 | if (startUpCounter == 10000)
40 | {
41 | Encoder.UpdateEncoderPoll();
42 | encoderOffset += Encoder.GetJointPosition();
43 | avgCounter++;
44 |
45 | if (avgCounter == 100)
46 | {
47 | done = 1;
48 | encoderOffset /= 100.0f;
49 | SetInverterPWMDuty(0x0, 0x0, 0x0);
50 | return;
51 | }
52 | }
53 | else
54 | {
55 | startUpCounter++;
56 | }
57 | }
58 |
59 | else
60 | {
61 | SetInverterPWMDuty(0x0, 0x0, 0x0);
62 | ADCCalibration(1);
63 |
64 | if (startUpCounter == 1000)
65 | {
66 | ADC1Offset += (int32_t) GetSO1();
67 | ADC2Offset += (int32_t) GetSO2();
68 | avgCounter++;
69 |
70 | if (avgCounter == 100)
71 | {
72 | startUpCounter = 0;
73 | ADC1Offset /= 100;
74 | ADC2Offset /= 100;
75 | EncoderCalibration = 1;
76 | avgCounter = 0;
77 |
78 | ADCCalibration(0);
79 |
80 | return;
81 | }
82 | }
83 | else
84 | {
85 | startUpCounter++;
86 | }
87 | }
88 | }
89 |
90 | }
91 |
92 | void Calibration::DQZTrans(float a, float b, float c, float theta, float *d, float *q)
93 | {
94 | float cf = FastCos(theta);
95 | float sf = FastSin(theta);
96 |
97 | *d = 0.6666667f * (cf * a + (0.86602540378f * sf - 0.5f * cf) * b + (-0.86602540378f * sf - 0.5f * cf) * c);
98 | *q = 0.6666667f * (-sf * a - (-0.86602540378f * cf - 0.5f * sf) * b - (0.86602540378f * cf - 0.5f * sf) * c);
99 | }
100 |
101 | void Calibration::DQZTransInv(float d, float q, float theta, float *a, float *b, float *c)
102 | {
103 | if (d > 0.9f)
104 | d = 0.9f;
105 | if (d < -0.9f)
106 | d = -0.9f;
107 |
108 | if (q > 0.9f)
109 | q = 0.9f;
110 | if (q < -0.9f)
111 | q = -0.9f;
112 |
113 | float cf = FastCos(theta);
114 | float sf = FastSin(theta);
115 |
116 | *a = cf * d - sf * q;
117 | *b = (0.86602540378f * sf - 0.5f * cf) * d - (-0.86602540378f * cf - 0.5f * sf) * q;
118 | *c = (-0.86602540378f * sf - 0.5f * cf) * d - (0.86602540378f * cf - 0.5f * sf) * q;
119 | }
120 |
--------------------------------------------------------------------------------
/Calibration/calibration.hpp:
--------------------------------------------------------------------------------
1 | #ifndef CALIBRATION_HPP_
2 | #define CALIBRATION_HPP_
3 |
4 | #define _USE_MATH_DEFINES
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 |
13 | class Calibration {
14 | public:
15 | void Init();
16 | void SetControlTable(ControlTable *_controlTable);
17 | void CalibrationUpdate();
18 |
19 | uint8_t done = 0;
20 | float encoderOffset = 0.0f;
21 | int32_t ADC1Offset = 0;
22 | int32_t ADC2Offset = 0;
23 |
24 | private:
25 | ControlTable *controlTable;
26 | AS5047 Encoder = AS5047();
27 |
28 | uint32_t startUpCounter = 0;
29 | uint32_t avgCounter = 0;
30 | uint8_t EncoderCalibration = 0;
31 |
32 | void DQZTrans(float a, float b, float c, float theta, float *d, float *q);
33 | void DQZTransInv(float d, float q, float theta, float *a, float *b, float *c);
34 | };
35 |
36 |
37 | #endif
38 |
--------------------------------------------------------------------------------
/Core/Inc/adc.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : ADC.h
4 | * Description : This file provides code for the configuration
5 | * of the ADC instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __adc_H
21 | #define __adc_H
22 | #ifdef __cplusplus
23 | extern "C" {
24 | #endif
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | #include "main.h"
28 |
29 | /* USER CODE BEGIN Includes */
30 |
31 | /* USER CODE END Includes */
32 |
33 | extern ADC_HandleTypeDef hadc1;
34 | extern ADC_HandleTypeDef hadc2;
35 | extern ADC_HandleTypeDef hadc3;
36 |
37 | /* USER CODE BEGIN Private defines */
38 |
39 | /* USER CODE END Private defines */
40 |
41 | void MX_ADC1_Init(void);
42 | void MX_ADC2_Init(void);
43 | void MX_ADC3_Init(void);
44 |
45 | /* USER CODE BEGIN Prototypes */
46 |
47 | /* USER CODE END Prototypes */
48 |
49 | #ifdef __cplusplus
50 | }
51 | #endif
52 | #endif /*__ adc_H */
53 |
54 | /**
55 | * @}
56 | */
57 |
58 | /**
59 | * @}
60 | */
61 |
62 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
63 |
--------------------------------------------------------------------------------
/Core/Inc/crc.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : CRC.h
4 | * Description : This file provides code for the configuration
5 | * of the CRC instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __crc_H
21 | #define __crc_H
22 | #ifdef __cplusplus
23 | extern "C" {
24 | #endif
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | #include "main.h"
28 |
29 | /* USER CODE BEGIN Includes */
30 |
31 | /* USER CODE END Includes */
32 |
33 | extern CRC_HandleTypeDef hcrc;
34 |
35 | /* USER CODE BEGIN Private defines */
36 |
37 | /* USER CODE END Private defines */
38 |
39 | void MX_CRC_Init(void);
40 |
41 | /* USER CODE BEGIN Prototypes */
42 |
43 | /* USER CODE END Prototypes */
44 |
45 | #ifdef __cplusplus
46 | }
47 | #endif
48 | #endif /*__ crc_H */
49 |
50 | /**
51 | * @}
52 | */
53 |
54 | /**
55 | * @}
56 | */
57 |
58 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
59 |
--------------------------------------------------------------------------------
/Core/Inc/dma.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : dma.h
4 | * Description : This file contains all the function prototypes for
5 | * the dma.c file
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __dma_H
21 | #define __dma_H
22 |
23 | #ifdef __cplusplus
24 | extern "C" {
25 | #endif
26 |
27 | /* Includes ------------------------------------------------------------------*/
28 | #include "main.h"
29 |
30 | /* DMA memory to memory transfer handles -------------------------------------*/
31 |
32 | /* USER CODE BEGIN Includes */
33 |
34 | /* USER CODE END Includes */
35 |
36 | /* USER CODE BEGIN Private defines */
37 |
38 | /* USER CODE END Private defines */
39 |
40 | void MX_DMA_Init(void);
41 |
42 | /* USER CODE BEGIN Prototypes */
43 |
44 | /* USER CODE END Prototypes */
45 |
46 | #ifdef __cplusplus
47 | }
48 | #endif
49 |
50 | #endif /* __dma_H */
51 |
52 | /**
53 | * @}
54 | */
55 |
56 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
57 |
--------------------------------------------------------------------------------
/Core/Inc/gpio.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : gpio.h
4 | * Description : This file contains all the functions prototypes for
5 | * the gpio
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef __gpio_H
22 | #define __gpio_H
23 | #ifdef __cplusplus
24 | extern "C" {
25 | #endif
26 |
27 | /* Includes ------------------------------------------------------------------*/
28 | #include "main.h"
29 |
30 | /* USER CODE BEGIN Includes */
31 |
32 | /* USER CODE END Includes */
33 |
34 | /* USER CODE BEGIN Private defines */
35 |
36 | /* USER CODE END Private defines */
37 |
38 | void MX_GPIO_Init(void);
39 |
40 | /* USER CODE BEGIN Prototypes */
41 |
42 | /* USER CODE END Prototypes */
43 |
44 | #ifdef __cplusplus
45 | }
46 | #endif
47 | #endif /*__ pinoutConfig_H */
48 |
49 | /**
50 | * @}
51 | */
52 |
53 | /**
54 | * @}
55 | */
56 |
57 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
58 |
--------------------------------------------------------------------------------
/Core/Inc/jdrive_main.hpp:
--------------------------------------------------------------------------------
1 | #ifdef __cplusplus
2 | extern "C" {
3 | #endif
4 |
5 | #ifndef INC_JDRIVE_MAIN_HPP_
6 | #define INC_JDRIVE_MAIN_HPP_
7 |
8 | enum ControlStatus
9 | {
10 | STATUS_NONE,
11 | STATUS_MOTORCONTROL,
12 | STATUS_CALIBRATION
13 | };
14 |
15 | void JDriveMain();
16 |
17 | #endif
18 |
19 | #ifdef __cplusplus
20 | }
21 | #endif
22 |
--------------------------------------------------------------------------------
/Core/Inc/main.h:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file : main.h
5 | * @brief : Header for main.c file.
6 | * This file contains the common defines of the application.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2020 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 | /* USER CODE END Header */
21 |
22 | /* Define to prevent recursive inclusion -------------------------------------*/
23 | #ifndef __MAIN_H
24 | #define __MAIN_H
25 |
26 | #ifdef __cplusplus
27 | extern "C" {
28 | #endif
29 |
30 | /* Includes ------------------------------------------------------------------*/
31 | #include "stm32f4xx_hal.h"
32 |
33 | /* Private includes ----------------------------------------------------------*/
34 | /* USER CODE BEGIN Includes */
35 |
36 | /* USER CODE END Includes */
37 |
38 | /* Exported types ------------------------------------------------------------*/
39 | /* USER CODE BEGIN ET */
40 |
41 | /* USER CODE END ET */
42 |
43 | /* Exported constants --------------------------------------------------------*/
44 | /* USER CODE BEGIN EC */
45 |
46 | /* USER CODE END EC */
47 |
48 | /* Exported macro ------------------------------------------------------------*/
49 | /* USER CODE BEGIN EM */
50 |
51 | /* USER CODE END EM */
52 |
53 | /* Exported functions prototypes ---------------------------------------------*/
54 | void Error_Handler(void);
55 |
56 | /* USER CODE BEGIN EFP */
57 |
58 | /* USER CODE END EFP */
59 |
60 | /* Private defines -----------------------------------------------------------*/
61 | #define DEADTIME_CLK 0
62 | #define FET_Temp_Pin GPIO_PIN_0
63 | #define FET_Temp_GPIO_Port GPIOC
64 | #define Encoder_MOSI_Pin GPIO_PIN_1
65 | #define Encoder_MOSI_GPIO_Port GPIOC
66 | #define Encoder_MISO_Pin GPIO_PIN_2
67 | #define Encoder_MISO_GPIO_Port GPIOC
68 | #define Encoder_CS_Pin GPIO_PIN_3
69 | #define Encoder_CS_GPIO_Port GPIOC
70 | #define DC_Voltage_Pin GPIO_PIN_0
71 | #define DC_Voltage_GPIO_Port GPIOA
72 | #define Motor_Temp_Pin GPIO_PIN_1
73 | #define Motor_Temp_GPIO_Port GPIOA
74 | #define ControlBus_TX_Pin GPIO_PIN_2
75 | #define ControlBus_TX_GPIO_Port GPIOA
76 | #define ControlBus_RX_Pin GPIO_PIN_3
77 | #define ControlBus_RX_GPIO_Port GPIOA
78 | #define ControlBus_TXEN_Pin GPIO_PIN_4
79 | #define ControlBus_TXEN_GPIO_Port GPIOA
80 | #define AL_Pin GPIO_PIN_7
81 | #define AL_GPIO_Port GPIOA
82 | #define A_Current_Pin GPIO_PIN_4
83 | #define A_Current_GPIO_Port GPIOC
84 | #define B_Current_Pin GPIO_PIN_5
85 | #define B_Current_GPIO_Port GPIOC
86 | #define BL_Pin GPIO_PIN_0
87 | #define BL_GPIO_Port GPIOB
88 | #define CL_Pin GPIO_PIN_1
89 | #define CL_GPIO_Port GPIOB
90 | #define LED_Pin GPIO_PIN_2
91 | #define LED_GPIO_Port GPIOB
92 | #define Encoder_SCK_Pin GPIO_PIN_10
93 | #define Encoder_SCK_GPIO_Port GPIOB
94 | #define EN_GATE_Pin GPIO_PIN_7
95 | #define EN_GATE_GPIO_Port GPIOC
96 | #define DC_CAL_Pin GPIO_PIN_8
97 | #define DC_CAL_GPIO_Port GPIOC
98 | #define nFAULT_Pin GPIO_PIN_9
99 | #define nFAULT_GPIO_Port GPIOC
100 | #define AH_Pin GPIO_PIN_8
101 | #define AH_GPIO_Port GPIOA
102 | #define BH_Pin GPIO_PIN_9
103 | #define BH_GPIO_Port GPIOA
104 | #define CH_Pin GPIO_PIN_10
105 | #define CH_GPIO_Port GPIOA
106 | #define TMS_Pin GPIO_PIN_13
107 | #define TMS_GPIO_Port GPIOA
108 | #define TCK_Pin GPIO_PIN_14
109 | #define TCK_GPIO_Port GPIOA
110 | #define TP0_Pin GPIO_PIN_10
111 | #define TP0_GPIO_Port GPIOC
112 | #define TP1_Pin GPIO_PIN_11
113 | #define TP1_GPIO_Port GPIOC
114 | #define SWO_Pin GPIO_PIN_3
115 | #define SWO_GPIO_Port GPIOB
116 | /* USER CODE BEGIN Private defines */
117 |
118 | /* USER CODE END Private defines */
119 |
120 | #ifdef __cplusplus
121 | }
122 | #endif
123 |
124 | #endif /* __MAIN_H */
125 |
126 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
127 |
--------------------------------------------------------------------------------
/Core/Inc/spi.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : SPI.h
4 | * Description : This file provides code for the configuration
5 | * of the SPI instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __spi_H
21 | #define __spi_H
22 | #ifdef __cplusplus
23 | extern "C" {
24 | #endif
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | #include "main.h"
28 |
29 | /* USER CODE BEGIN Includes */
30 |
31 | /* USER CODE END Includes */
32 |
33 | extern SPI_HandleTypeDef hspi2;
34 |
35 | /* USER CODE BEGIN Private defines */
36 |
37 | /* USER CODE END Private defines */
38 |
39 | void MX_SPI2_Init(void);
40 |
41 | /* USER CODE BEGIN Prototypes */
42 |
43 | /* USER CODE END Prototypes */
44 |
45 | #ifdef __cplusplus
46 | }
47 | #endif
48 | #endif /*__ spi_H */
49 |
50 | /**
51 | * @}
52 | */
53 |
54 | /**
55 | * @}
56 | */
57 |
58 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
59 |
--------------------------------------------------------------------------------
/Core/Inc/stm32f4xx_it.h:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file stm32f4xx_it.h
5 | * @brief This file contains the headers of the interrupt handlers.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* USER CODE END Header */
20 |
21 | /* Define to prevent recursive inclusion -------------------------------------*/
22 | #ifndef __STM32F4xx_IT_H
23 | #define __STM32F4xx_IT_H
24 |
25 | #ifdef __cplusplus
26 | extern "C" {
27 | #endif
28 |
29 | /* Private includes ----------------------------------------------------------*/
30 | /* USER CODE BEGIN Includes */
31 |
32 | /* USER CODE END Includes */
33 |
34 | /* Exported types ------------------------------------------------------------*/
35 | /* USER CODE BEGIN ET */
36 |
37 | /* USER CODE END ET */
38 |
39 | /* Exported constants --------------------------------------------------------*/
40 | /* USER CODE BEGIN EC */
41 |
42 | /* USER CODE END EC */
43 |
44 | /* Exported macro ------------------------------------------------------------*/
45 | /* USER CODE BEGIN EM */
46 |
47 | /* USER CODE END EM */
48 |
49 | /* Exported functions prototypes ---------------------------------------------*/
50 | void NMI_Handler(void);
51 | void HardFault_Handler(void);
52 | void MemManage_Handler(void);
53 | void BusFault_Handler(void);
54 | void UsageFault_Handler(void);
55 | void SVC_Handler(void);
56 | void DebugMon_Handler(void);
57 | void PendSV_Handler(void);
58 | void SysTick_Handler(void);
59 | void DMA1_Stream5_IRQHandler(void);
60 | void TIM1_UP_TIM10_IRQHandler(void);
61 | void SPI2_IRQHandler(void);
62 | void USART2_IRQHandler(void);
63 | void TIM8_UP_TIM13_IRQHandler(void);
64 | /* USER CODE BEGIN EFP */
65 |
66 | /* USER CODE END EFP */
67 |
68 | #ifdef __cplusplus
69 | }
70 | #endif
71 |
72 | #endif /* __STM32F4xx_IT_H */
73 |
74 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
75 |
--------------------------------------------------------------------------------
/Core/Inc/tim.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : TIM.h
4 | * Description : This file provides code for the configuration
5 | * of the TIM instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __tim_H
21 | #define __tim_H
22 | #ifdef __cplusplus
23 | extern "C" {
24 | #endif
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | #include "main.h"
28 |
29 | /* USER CODE BEGIN Includes */
30 |
31 | /* USER CODE END Includes */
32 |
33 | extern TIM_HandleTypeDef htim1;
34 | extern TIM_HandleTypeDef htim2;
35 | extern TIM_HandleTypeDef htim8;
36 |
37 | /* USER CODE BEGIN Private defines */
38 |
39 | /* USER CODE END Private defines */
40 |
41 | void MX_TIM1_Init(void);
42 | void MX_TIM2_Init(void);
43 | void MX_TIM8_Init(void);
44 |
45 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
46 |
47 | /* USER CODE BEGIN Prototypes */
48 |
49 | /* USER CODE END Prototypes */
50 |
51 | #ifdef __cplusplus
52 | }
53 | #endif
54 | #endif /*__ tim_H */
55 |
56 | /**
57 | * @}
58 | */
59 |
60 | /**
61 | * @}
62 | */
63 |
64 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
65 |
--------------------------------------------------------------------------------
/Core/Inc/usart.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : USART.h
4 | * Description : This file provides code for the configuration
5 | * of the USART instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* Define to prevent recursive inclusion -------------------------------------*/
20 | #ifndef __usart_H
21 | #define __usart_H
22 | #ifdef __cplusplus
23 | extern "C" {
24 | #endif
25 |
26 | /* Includes ------------------------------------------------------------------*/
27 | #include "main.h"
28 |
29 | /* USER CODE BEGIN Includes */
30 |
31 | /* USER CODE END Includes */
32 |
33 | extern UART_HandleTypeDef huart2;
34 |
35 | /* USER CODE BEGIN Private defines */
36 |
37 | /* USER CODE END Private defines */
38 |
39 | void MX_USART2_UART_Init(void);
40 |
41 | /* USER CODE BEGIN Prototypes */
42 |
43 | /* USER CODE END Prototypes */
44 |
45 | #ifdef __cplusplus
46 | }
47 | #endif
48 | #endif /*__ usart_H */
49 |
50 | /**
51 | * @}
52 | */
53 |
54 | /**
55 | * @}
56 | */
57 |
58 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
59 |
--------------------------------------------------------------------------------
/Core/Src/adc.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : ADC.c
4 | * Description : This file provides code for the configuration
5 | * of the ADC instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "adc.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | ADC_HandleTypeDef hadc1;
28 | ADC_HandleTypeDef hadc2;
29 | ADC_HandleTypeDef hadc3;
30 |
31 | /* ADC1 init function */
32 | void MX_ADC1_Init(void)
33 | {
34 | ADC_ChannelConfTypeDef sConfig = {0};
35 |
36 | /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
37 | */
38 | hadc1.Instance = ADC1;
39 | hadc1.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
40 | hadc1.Init.Resolution = ADC_RESOLUTION_12B;
41 | hadc1.Init.ScanConvMode = DISABLE;
42 | hadc1.Init.ContinuousConvMode = DISABLE;
43 | hadc1.Init.DiscontinuousConvMode = DISABLE;
44 | hadc1.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
45 | hadc1.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO;
46 | hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT;
47 | hadc1.Init.NbrOfConversion = 1;
48 | hadc1.Init.DMAContinuousRequests = DISABLE;
49 | hadc1.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
50 | if (HAL_ADC_Init(&hadc1) != HAL_OK)
51 | {
52 | Error_Handler();
53 | }
54 | /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.
55 | */
56 | sConfig.Channel = ADC_CHANNEL_14;
57 | sConfig.Rank = 1;
58 | sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES;
59 | if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK)
60 | {
61 | Error_Handler();
62 | }
63 |
64 | }
65 | /* ADC2 init function */
66 | void MX_ADC2_Init(void)
67 | {
68 | ADC_ChannelConfTypeDef sConfig = {0};
69 |
70 | /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
71 | */
72 | hadc2.Instance = ADC2;
73 | hadc2.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
74 | hadc2.Init.Resolution = ADC_RESOLUTION_12B;
75 | hadc2.Init.ScanConvMode = DISABLE;
76 | hadc2.Init.ContinuousConvMode = DISABLE;
77 | hadc2.Init.DiscontinuousConvMode = DISABLE;
78 | hadc2.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
79 | hadc2.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO;
80 | hadc2.Init.DataAlign = ADC_DATAALIGN_RIGHT;
81 | hadc2.Init.NbrOfConversion = 1;
82 | hadc2.Init.DMAContinuousRequests = DISABLE;
83 | hadc2.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
84 | if (HAL_ADC_Init(&hadc2) != HAL_OK)
85 | {
86 | Error_Handler();
87 | }
88 | /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.
89 | */
90 | sConfig.Channel = ADC_CHANNEL_15;
91 | sConfig.Rank = 1;
92 | sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES;
93 | if (HAL_ADC_ConfigChannel(&hadc2, &sConfig) != HAL_OK)
94 | {
95 | Error_Handler();
96 | }
97 |
98 | }
99 | /* ADC3 init function */
100 | void MX_ADC3_Init(void)
101 | {
102 | ADC_ChannelConfTypeDef sConfig = {0};
103 |
104 | /** Configure the global features of the ADC (Clock, Resolution, Data Alignment and number of conversion)
105 | */
106 | hadc3.Instance = ADC3;
107 | hadc3.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4;
108 | hadc3.Init.Resolution = ADC_RESOLUTION_12B;
109 | hadc3.Init.ScanConvMode = ENABLE;
110 | hadc3.Init.ContinuousConvMode = DISABLE;
111 | hadc3.Init.DiscontinuousConvMode = ENABLE;
112 | hadc3.Init.NbrOfDiscConversion = 1;
113 | hadc3.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING;
114 | hadc3.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO;
115 | hadc3.Init.DataAlign = ADC_DATAALIGN_RIGHT;
116 | hadc3.Init.NbrOfConversion = 3;
117 | hadc3.Init.DMAContinuousRequests = DISABLE;
118 | hadc3.Init.EOCSelection = ADC_EOC_SINGLE_CONV;
119 | if (HAL_ADC_Init(&hadc3) != HAL_OK)
120 | {
121 | Error_Handler();
122 | }
123 | /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.
124 | */
125 | sConfig.Channel = ADC_CHANNEL_0;
126 | sConfig.Rank = 1;
127 | sConfig.SamplingTime = ADC_SAMPLETIME_3CYCLES;
128 | if (HAL_ADC_ConfigChannel(&hadc3, &sConfig) != HAL_OK)
129 | {
130 | Error_Handler();
131 | }
132 | /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.
133 | */
134 | sConfig.Channel = ADC_CHANNEL_1;
135 | sConfig.Rank = 2;
136 | if (HAL_ADC_ConfigChannel(&hadc3, &sConfig) != HAL_OK)
137 | {
138 | Error_Handler();
139 | }
140 | /** Configure for the selected ADC regular channel its corresponding rank in the sequencer and its sample time.
141 | */
142 | sConfig.Channel = ADC_CHANNEL_10;
143 | sConfig.Rank = 3;
144 | if (HAL_ADC_ConfigChannel(&hadc3, &sConfig) != HAL_OK)
145 | {
146 | Error_Handler();
147 | }
148 |
149 | }
150 |
151 | void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle)
152 | {
153 |
154 | GPIO_InitTypeDef GPIO_InitStruct = {0};
155 | if(adcHandle->Instance==ADC1)
156 | {
157 | /* USER CODE BEGIN ADC1_MspInit 0 */
158 |
159 | /* USER CODE END ADC1_MspInit 0 */
160 | /* ADC1 clock enable */
161 | __HAL_RCC_ADC1_CLK_ENABLE();
162 |
163 | __HAL_RCC_GPIOC_CLK_ENABLE();
164 | /**ADC1 GPIO Configuration
165 | PC4 ------> ADC1_IN14
166 | */
167 | GPIO_InitStruct.Pin = A_Current_Pin;
168 | GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
169 | GPIO_InitStruct.Pull = GPIO_NOPULL;
170 | HAL_GPIO_Init(A_Current_GPIO_Port, &GPIO_InitStruct);
171 |
172 | /* USER CODE BEGIN ADC1_MspInit 1 */
173 |
174 | /* USER CODE END ADC1_MspInit 1 */
175 | }
176 | else if(adcHandle->Instance==ADC2)
177 | {
178 | /* USER CODE BEGIN ADC2_MspInit 0 */
179 |
180 | /* USER CODE END ADC2_MspInit 0 */
181 | /* ADC2 clock enable */
182 | __HAL_RCC_ADC2_CLK_ENABLE();
183 |
184 | __HAL_RCC_GPIOC_CLK_ENABLE();
185 | /**ADC2 GPIO Configuration
186 | PC5 ------> ADC2_IN15
187 | */
188 | GPIO_InitStruct.Pin = B_Current_Pin;
189 | GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
190 | GPIO_InitStruct.Pull = GPIO_NOPULL;
191 | HAL_GPIO_Init(B_Current_GPIO_Port, &GPIO_InitStruct);
192 |
193 | /* USER CODE BEGIN ADC2_MspInit 1 */
194 |
195 | /* USER CODE END ADC2_MspInit 1 */
196 | }
197 | else if(adcHandle->Instance==ADC3)
198 | {
199 | /* USER CODE BEGIN ADC3_MspInit 0 */
200 |
201 | /* USER CODE END ADC3_MspInit 0 */
202 | /* ADC3 clock enable */
203 | __HAL_RCC_ADC3_CLK_ENABLE();
204 |
205 | __HAL_RCC_GPIOC_CLK_ENABLE();
206 | __HAL_RCC_GPIOA_CLK_ENABLE();
207 | /**ADC3 GPIO Configuration
208 | PC0 ------> ADC3_IN10
209 | PA0-WKUP ------> ADC3_IN0
210 | PA1 ------> ADC3_IN1
211 | */
212 | GPIO_InitStruct.Pin = FET_Temp_Pin;
213 | GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
214 | GPIO_InitStruct.Pull = GPIO_NOPULL;
215 | HAL_GPIO_Init(FET_Temp_GPIO_Port, &GPIO_InitStruct);
216 |
217 | GPIO_InitStruct.Pin = DC_Voltage_Pin|Motor_Temp_Pin;
218 | GPIO_InitStruct.Mode = GPIO_MODE_ANALOG;
219 | GPIO_InitStruct.Pull = GPIO_NOPULL;
220 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
221 |
222 | /* USER CODE BEGIN ADC3_MspInit 1 */
223 |
224 | /* USER CODE END ADC3_MspInit 1 */
225 | }
226 | }
227 |
228 | void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle)
229 | {
230 |
231 | if(adcHandle->Instance==ADC1)
232 | {
233 | /* USER CODE BEGIN ADC1_MspDeInit 0 */
234 |
235 | /* USER CODE END ADC1_MspDeInit 0 */
236 | /* Peripheral clock disable */
237 | __HAL_RCC_ADC1_CLK_DISABLE();
238 |
239 | /**ADC1 GPIO Configuration
240 | PC4 ------> ADC1_IN14
241 | */
242 | HAL_GPIO_DeInit(A_Current_GPIO_Port, A_Current_Pin);
243 |
244 | /* USER CODE BEGIN ADC1_MspDeInit 1 */
245 |
246 | /* USER CODE END ADC1_MspDeInit 1 */
247 | }
248 | else if(adcHandle->Instance==ADC2)
249 | {
250 | /* USER CODE BEGIN ADC2_MspDeInit 0 */
251 |
252 | /* USER CODE END ADC2_MspDeInit 0 */
253 | /* Peripheral clock disable */
254 | __HAL_RCC_ADC2_CLK_DISABLE();
255 |
256 | /**ADC2 GPIO Configuration
257 | PC5 ------> ADC2_IN15
258 | */
259 | HAL_GPIO_DeInit(B_Current_GPIO_Port, B_Current_Pin);
260 |
261 | /* USER CODE BEGIN ADC2_MspDeInit 1 */
262 |
263 | /* USER CODE END ADC2_MspDeInit 1 */
264 | }
265 | else if(adcHandle->Instance==ADC3)
266 | {
267 | /* USER CODE BEGIN ADC3_MspDeInit 0 */
268 |
269 | /* USER CODE END ADC3_MspDeInit 0 */
270 | /* Peripheral clock disable */
271 | __HAL_RCC_ADC3_CLK_DISABLE();
272 |
273 | /**ADC3 GPIO Configuration
274 | PC0 ------> ADC3_IN10
275 | PA0-WKUP ------> ADC3_IN0
276 | PA1 ------> ADC3_IN1
277 | */
278 | HAL_GPIO_DeInit(FET_Temp_GPIO_Port, FET_Temp_Pin);
279 |
280 | HAL_GPIO_DeInit(GPIOA, DC_Voltage_Pin|Motor_Temp_Pin);
281 |
282 | /* USER CODE BEGIN ADC3_MspDeInit 1 */
283 |
284 | /* USER CODE END ADC3_MspDeInit 1 */
285 | }
286 | }
287 |
288 | /* USER CODE BEGIN 1 */
289 |
290 | /* USER CODE END 1 */
291 |
292 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
293 |
--------------------------------------------------------------------------------
/Core/Src/crc.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : CRC.c
4 | * Description : This file provides code for the configuration
5 | * of the CRC instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "crc.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | CRC_HandleTypeDef hcrc;
28 |
29 | /* CRC init function */
30 | void MX_CRC_Init(void)
31 | {
32 |
33 | hcrc.Instance = CRC;
34 | if (HAL_CRC_Init(&hcrc) != HAL_OK)
35 | {
36 | Error_Handler();
37 | }
38 |
39 | }
40 |
41 | void HAL_CRC_MspInit(CRC_HandleTypeDef* crcHandle)
42 | {
43 |
44 | if(crcHandle->Instance==CRC)
45 | {
46 | /* USER CODE BEGIN CRC_MspInit 0 */
47 |
48 | /* USER CODE END CRC_MspInit 0 */
49 | /* CRC clock enable */
50 | __HAL_RCC_CRC_CLK_ENABLE();
51 | /* USER CODE BEGIN CRC_MspInit 1 */
52 |
53 | /* USER CODE END CRC_MspInit 1 */
54 | }
55 | }
56 |
57 | void HAL_CRC_MspDeInit(CRC_HandleTypeDef* crcHandle)
58 | {
59 |
60 | if(crcHandle->Instance==CRC)
61 | {
62 | /* USER CODE BEGIN CRC_MspDeInit 0 */
63 |
64 | /* USER CODE END CRC_MspDeInit 0 */
65 | /* Peripheral clock disable */
66 | __HAL_RCC_CRC_CLK_DISABLE();
67 | /* USER CODE BEGIN CRC_MspDeInit 1 */
68 |
69 | /* USER CODE END CRC_MspDeInit 1 */
70 | }
71 | }
72 |
73 | /* USER CODE BEGIN 1 */
74 |
75 | /* USER CODE END 1 */
76 |
77 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
78 |
--------------------------------------------------------------------------------
/Core/Src/dma.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : dma.c
4 | * Description : This file provides code for the configuration
5 | * of all the requested memory to memory DMA transfers.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "dma.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | /*----------------------------------------------------------------------------*/
28 | /* Configure DMA */
29 | /*----------------------------------------------------------------------------*/
30 |
31 | /* USER CODE BEGIN 1 */
32 |
33 | /* USER CODE END 1 */
34 |
35 | /**
36 | * Enable DMA controller clock
37 | */
38 | void MX_DMA_Init(void)
39 | {
40 |
41 | /* DMA controller clock enable */
42 | __HAL_RCC_DMA1_CLK_ENABLE();
43 |
44 | /* DMA interrupt init */
45 | /* DMA1_Stream5_IRQn interrupt configuration */
46 | HAL_NVIC_SetPriority(DMA1_Stream5_IRQn, 0, 0);
47 | HAL_NVIC_EnableIRQ(DMA1_Stream5_IRQn);
48 |
49 | }
50 |
51 | /* USER CODE BEGIN 2 */
52 |
53 | /* USER CODE END 2 */
54 |
55 | /**
56 | * @}
57 | */
58 |
59 | /**
60 | * @}
61 | */
62 |
63 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
64 |
--------------------------------------------------------------------------------
/Core/Src/gpio.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : gpio.c
4 | * Description : This file provides code for the configuration
5 | * of all used GPIO pins.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "gpio.h"
22 | /* USER CODE BEGIN 0 */
23 |
24 | /* USER CODE END 0 */
25 |
26 | /*----------------------------------------------------------------------------*/
27 | /* Configure GPIO */
28 | /*----------------------------------------------------------------------------*/
29 | /* USER CODE BEGIN 1 */
30 |
31 | /* USER CODE END 1 */
32 |
33 | /** Configure pins as
34 | * Analog
35 | * Input
36 | * Output
37 | * EVENT_OUT
38 | * EXTI
39 | */
40 | void MX_GPIO_Init(void)
41 | {
42 |
43 | GPIO_InitTypeDef GPIO_InitStruct = {0};
44 |
45 | /* GPIO Ports Clock Enable */
46 | __HAL_RCC_GPIOC_CLK_ENABLE();
47 | __HAL_RCC_GPIOA_CLK_ENABLE();
48 | __HAL_RCC_GPIOB_CLK_ENABLE();
49 |
50 | /*Configure GPIO pin Output Level */
51 | HAL_GPIO_WritePin(GPIOC, Encoder_CS_Pin|EN_GATE_Pin|DC_CAL_Pin|TP0_Pin
52 | |TP1_Pin, GPIO_PIN_RESET);
53 |
54 | /*Configure GPIO pin Output Level */
55 | HAL_GPIO_WritePin(ControlBus_TXEN_GPIO_Port, ControlBus_TXEN_Pin, GPIO_PIN_RESET);
56 |
57 | /*Configure GPIO pins : PCPin PCPin PCPin */
58 | GPIO_InitStruct.Pin = Encoder_CS_Pin|EN_GATE_Pin|DC_CAL_Pin;
59 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
60 | GPIO_InitStruct.Pull = GPIO_NOPULL;
61 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
62 | HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
63 |
64 | /*Configure GPIO pin : PtPin */
65 | GPIO_InitStruct.Pin = ControlBus_TXEN_Pin;
66 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
67 | GPIO_InitStruct.Pull = GPIO_NOPULL;
68 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
69 | HAL_GPIO_Init(ControlBus_TXEN_GPIO_Port, &GPIO_InitStruct);
70 |
71 | /*Configure GPIO pin : PtPin */
72 | GPIO_InitStruct.Pin = nFAULT_Pin;
73 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
74 | GPIO_InitStruct.Pull = GPIO_PULLUP;
75 | HAL_GPIO_Init(nFAULT_GPIO_Port, &GPIO_InitStruct);
76 |
77 | /*Configure GPIO pins : PCPin PCPin */
78 | GPIO_InitStruct.Pin = TP0_Pin|TP1_Pin;
79 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
80 | GPIO_InitStruct.Pull = GPIO_NOPULL;
81 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
82 | HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
83 |
84 | }
85 |
86 | /* USER CODE BEGIN 2 */
87 |
88 | /* USER CODE END 2 */
89 |
90 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
91 |
--------------------------------------------------------------------------------
/Core/Src/jdrive_main.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 |
12 | MotorControl motorControl = MotorControl();
13 | Calibration calibration = Calibration();
14 | Protection protection = Protection();
15 | Protocol protocol = Protocol();
16 |
17 | ControlTable *controlTable;
18 |
19 | uint8_t controlStatus = STATUS_NONE;
20 |
21 | float presentSupplyVoltage;
22 | float presentBoardTemp;
23 |
24 | void Control();
25 |
26 | //TODO make error control code
27 | //TODO add TX FIFO and delay
28 |
29 | void JDriveMain()
30 | {
31 | StartOnBoardLED();
32 | for (uint8_t k = 0; k < 2; k++)
33 | {
34 | for (int16_t i = 0x0; i <= 0xFFF; i = i + 45)
35 | {
36 | SetOnBoardLED(i);
37 | Delaymillis(1);
38 | }
39 | for (int16_t i = 0xFFF; i >= 0x0; i = i - 45)
40 | {
41 | SetOnBoardLED(i);
42 | Delaymillis(1);
43 | }
44 | }
45 |
46 | protocol.controlTable.Init();
47 | controlTable = &protocol.controlTable;
48 |
49 | if (ReadEEPROM(2) > (uint32_t) 0xFE)
50 | {
51 | controlTable->FactoryReset();
52 | }
53 |
54 | controlTable->LoadControlTableFromEEPROM();
55 |
56 | switch (controlTable->controlTableData[3].data)
57 | {
58 | case 0:
59 | SetUartBuadRate(9600);
60 | break;
61 | case 1:
62 | SetUartBuadRate(57600);
63 | break;
64 | case 2:
65 | SetUartBuadRate(115200);
66 | break;
67 | case 3:
68 | SetUartBuadRate(1000000);
69 | break;
70 | case 4:
71 | SetUartBuadRate(2000000);
72 | break;
73 | default:
74 | SetUartBuadRate(9600);
75 | break;
76 | }
77 |
78 | FastMathInit();
79 | StartADC();
80 | SetControlFunc(Control);
81 | SetUartFIFO(&protocol.uartFIFO);
82 | StartControlTimer();
83 | StartUartInterrupt();
84 |
85 | motorControl.SetControlTable(&protocol.controlTable);
86 | calibration.SetControlTable(&protocol.controlTable);
87 | protection.SetControlTable(&protocol.controlTable);
88 |
89 | Delaymillis(1);
90 | for (uint8_t i = 0; i < 100; i++)
91 | {
92 | Delaymillis(1);
93 | motorControl.supplyVoltage += GetDCVoltageRaw() * DC_VOLTAGE_COEFF;
94 | }
95 | motorControl.supplyVoltage /= 100.0f;
96 | protection.supplyVoltage = motorControl.supplyVoltage;
97 |
98 | if (motorControl.supplyVoltage >= *(float*) &controlTable->controlTableData[12].data || motorControl.supplyVoltage <= *(float*) &controlTable->controlTableData[13].data)
99 | {
100 | while (1)
101 | {
102 | SetOnBoardLED(0xFFF);
103 | Delaymillis(100);
104 | SetOnBoardLED(0x0);
105 | Delaymillis(100);
106 | }
107 | }
108 |
109 | SetOnBoardLED(0xFFF);
110 | Delaymillis(500);
111 | SetOnBoardLED(0x0);
112 |
113 | SetPhaseOrder(controlTable->controlTableData[23].data);
114 |
115 | OffGateDriver();
116 | StartInverterPWM();
117 | motorControl.Init();
118 | calibration.Init();
119 | protection.Init();
120 |
121 | StartTimer();
122 |
123 | controlStatus = STATUS_NONE;
124 |
125 | while (1)
126 | {
127 | protocol.Update();
128 | }
129 | }
130 |
131 | uint32_t pos;
132 |
133 | void Control()
134 | {
135 | TimerUpdate();
136 |
137 | presentSupplyVoltage = (float) GetDCVoltageRaw() * DC_VOLTAGE_COEFF;
138 | presentBoardTemp = (float) GetFETTempRaw() * ONBOARD_TEMP_COEFF;
139 | controlTable->controlTableData[47].data = *(uint32_t*) &presentSupplyVoltage;
140 | controlTable->controlTableData[48].data = *(uint32_t*) &presentBoardTemp;
141 | controlTable->controlTableData[49].data = GetMotorTempRaw();
142 |
143 | controlTable->controlTableData[40].data = GetTimerTick();
144 |
145 | SetPhaseOrder(controlTable->controlTableData[23].data);
146 |
147 | motorControl.Encoder.polePair = controlTable->controlTableData[27].data;
148 | motorControl.motorParam.polePair = controlTable->controlTableData[27].data;
149 |
150 | if (controlTable->controlTableData[50].data == 1)
151 | {
152 | controlStatus = STATUS_CALIBRATION;
153 | }
154 |
155 | if (controlTable->controlTableData[28].data == 1)
156 | {
157 | OnGateDriver();
158 | }
159 | else
160 | {
161 | OffGateDriver();
162 | SetInverterPWMDuty(0x7FF, 0x7FF, 0x7FF);
163 | controlTable->controlTableData[29].data = 0;
164 | controlStatus = STATUS_NONE;
165 | }
166 |
167 | if (controlTable->controlTableData[29].data == 1 && controlStatus != STATUS_CALIBRATION && controlTable->controlTableData[28].data == 1)
168 | {
169 | controlStatus = STATUS_MOTORCONTROL;
170 | }
171 | else
172 | {
173 | if (controlStatus != STATUS_CALIBRATION)
174 | {
175 | SetInverterPWMDuty(0x7FF, 0x7FF, 0x7FF);
176 | controlStatus = STATUS_NONE;
177 | }
178 | }
179 |
180 | if (controlStatus != STATUS_NONE)
181 | {
182 | protection.Update();
183 |
184 | if (controlStatus == STATUS_MOTORCONTROL)
185 | {
186 | motorControl.ControlUpdate();
187 | }
188 | else if (controlStatus == STATUS_CALIBRATION)
189 | {
190 | SetOnBoardLED(0xFFF);
191 | calibration.CalibrationUpdate();
192 |
193 | if (calibration.done)
194 | {
195 | protocol.controlTable.SetTable(28, 0, 1);
196 | protocol.controlTable.SetTable(26, *(uint32_t*) &calibration.encoderOffset, 4);
197 | protocol.controlTable.SetTable(24, calibration.ADC1Offset, 4);
198 | protocol.controlTable.SetTable(25, calibration.ADC2Offset, 4);
199 | protocol.controlTable.SetTable(28, 1, 1);
200 |
201 | motorControl.Init();
202 | calibration.Init();
203 |
204 | protocol.controlTable.SetTable(50, 0, 1);
205 |
206 | controlStatus = STATUS_NONE;
207 | SetOnBoardLED(0x0);
208 | }
209 | }
210 | }
211 | }
212 |
--------------------------------------------------------------------------------
/Core/Src/main.c:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file : main.c
5 | * @brief : Main program body
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* USER CODE END Header */
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "main.h"
22 | #include "adc.h"
23 | #include "crc.h"
24 | #include "dma.h"
25 | #include "spi.h"
26 | #include "tim.h"
27 | #include "usart.h"
28 | #include "gpio.h"
29 |
30 | /* Private includes ----------------------------------------------------------*/
31 | /* USER CODE BEGIN Includes */
32 | #include
33 | /* USER CODE END Includes */
34 |
35 | /* Private typedef -----------------------------------------------------------*/
36 | /* USER CODE BEGIN PTD */
37 |
38 | /* USER CODE END PTD */
39 |
40 | /* Private define ------------------------------------------------------------*/
41 | /* USER CODE BEGIN PD */
42 | /* USER CODE END PD */
43 |
44 | /* Private macro -------------------------------------------------------------*/
45 | /* USER CODE BEGIN PM */
46 |
47 | /* USER CODE END PM */
48 |
49 | /* Private variables ---------------------------------------------------------*/
50 |
51 | /* USER CODE BEGIN PV */
52 |
53 | /* USER CODE END PV */
54 |
55 | /* Private function prototypes -----------------------------------------------*/
56 | void SystemClock_Config(void);
57 | /* USER CODE BEGIN PFP */
58 | int _write(int fd, char *str, int len)
59 | {
60 | HAL_GPIO_WritePin(ControlBus_TXEN_GPIO_Port, ControlBus_TXEN_Pin, GPIO_PIN_SET);
61 | HAL_UART_Transmit_IT(&huart2, (uint8_t *)str, len);
62 | return len;
63 | }
64 |
65 | /* USER CODE END PFP */
66 |
67 | /* Private user code ---------------------------------------------------------*/
68 | /* USER CODE BEGIN 0 */
69 |
70 | /* USER CODE END 0 */
71 |
72 | /**
73 | * @brief The application entry point.
74 | * @retval int
75 | */
76 | int main(void)
77 | {
78 | /* USER CODE BEGIN 1 */
79 |
80 | /* USER CODE END 1 */
81 |
82 | /* MCU Configuration--------------------------------------------------------*/
83 |
84 | /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
85 | HAL_Init();
86 |
87 | /* USER CODE BEGIN Init */
88 |
89 | /* USER CODE END Init */
90 |
91 | /* Configure the system clock */
92 | SystemClock_Config();
93 |
94 | /* USER CODE BEGIN SysInit */
95 |
96 | /* USER CODE END SysInit */
97 |
98 | /* Initialize all configured peripherals */
99 | MX_GPIO_Init();
100 | MX_DMA_Init();
101 | MX_TIM2_Init();
102 | MX_CRC_Init();
103 | MX_USART2_UART_Init();
104 | MX_ADC1_Init();
105 | MX_ADC2_Init();
106 | MX_ADC3_Init();
107 | MX_SPI2_Init();
108 | MX_TIM1_Init();
109 | MX_TIM8_Init();
110 | /* USER CODE BEGIN 2 */
111 | HAL_GPIO_WritePin(DC_CAL_GPIO_Port, DC_CAL_Pin, GPIO_PIN_RESET);
112 | HAL_GPIO_WritePin(EN_GATE_GPIO_Port, EN_GATE_Pin, GPIO_PIN_RESET);
113 |
114 | JDriveMain();
115 | /* USER CODE END 2 */
116 |
117 | /* Infinite loop */
118 | /* USER CODE BEGIN WHILE */
119 | while (1)
120 | {
121 | /* USER CODE END WHILE */
122 |
123 | /* USER CODE BEGIN 3 */
124 | }
125 | /* USER CODE END 3 */
126 | }
127 |
128 | /**
129 | * @brief System Clock Configuration
130 | * @retval None
131 | */
132 | void SystemClock_Config(void)
133 | {
134 | RCC_OscInitTypeDef RCC_OscInitStruct = {0};
135 | RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
136 |
137 | /** Configure the main internal regulator output voltage
138 | */
139 | __HAL_RCC_PWR_CLK_ENABLE();
140 | __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
141 | /** Initializes the RCC Oscillators according to the specified parameters
142 | * in the RCC_OscInitTypeDef structure.
143 | */
144 | RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
145 | RCC_OscInitStruct.HSIState = RCC_HSI_ON;
146 | RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
147 | RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
148 | RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
149 | RCC_OscInitStruct.PLL.PLLM = 8;
150 | RCC_OscInitStruct.PLL.PLLN = 180;
151 | RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
152 | RCC_OscInitStruct.PLL.PLLQ = 2;
153 | RCC_OscInitStruct.PLL.PLLR = 2;
154 | if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
155 | {
156 | Error_Handler();
157 | }
158 | /** Activate the Over-Drive mode
159 | */
160 | if (HAL_PWREx_EnableOverDrive() != HAL_OK)
161 | {
162 | Error_Handler();
163 | }
164 | /** Initializes the CPU, AHB and APB buses clocks
165 | */
166 | RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
167 | |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
168 | RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
169 | RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
170 | RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV4;
171 | RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV2;
172 |
173 | if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_5) != HAL_OK)
174 | {
175 | Error_Handler();
176 | }
177 | }
178 |
179 | /* USER CODE BEGIN 4 */
180 |
181 | /* USER CODE END 4 */
182 |
183 | /**
184 | * @brief This function is executed in case of error occurrence.
185 | * @retval None
186 | */
187 | void Error_Handler(void)
188 | {
189 | /* USER CODE BEGIN Error_Handler_Debug */
190 | /* User can add his own implementation to report the HAL error return state */
191 |
192 | /* USER CODE END Error_Handler_Debug */
193 | }
194 |
195 | #ifdef USE_FULL_ASSERT
196 | /**
197 | * @brief Reports the name of the source file and the source line number
198 | * where the assert_param error has occurred.
199 | * @param file: pointer to the source file name
200 | * @param line: assert_param error line source number
201 | * @retval None
202 | */
203 | void assert_failed(uint8_t *file, uint32_t line)
204 | {
205 | /* USER CODE BEGIN 6 */
206 | /* User can add his own implementation to report the file name and line number,
207 | tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
208 | /* USER CODE END 6 */
209 | }
210 | #endif /* USE_FULL_ASSERT */
211 |
212 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
213 |
--------------------------------------------------------------------------------
/Core/Src/spi.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : SPI.c
4 | * Description : This file provides code for the configuration
5 | * of the SPI instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "spi.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | SPI_HandleTypeDef hspi2;
28 |
29 | /* SPI2 init function */
30 | void MX_SPI2_Init(void)
31 | {
32 |
33 | hspi2.Instance = SPI2;
34 | hspi2.Init.Mode = SPI_MODE_MASTER;
35 | hspi2.Init.Direction = SPI_DIRECTION_2LINES;
36 | hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
37 | hspi2.Init.CLKPolarity = SPI_POLARITY_LOW;
38 | hspi2.Init.CLKPhase = SPI_PHASE_2EDGE;
39 | hspi2.Init.NSS = SPI_NSS_SOFT;
40 | hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
41 | hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
42 | hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
43 | hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
44 | hspi2.Init.CRCPolynomial = 10;
45 | if (HAL_SPI_Init(&hspi2) != HAL_OK)
46 | {
47 | Error_Handler();
48 | }
49 |
50 | }
51 |
52 | void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
53 | {
54 |
55 | GPIO_InitTypeDef GPIO_InitStruct = {0};
56 | if(spiHandle->Instance==SPI2)
57 | {
58 | /* USER CODE BEGIN SPI2_MspInit 0 */
59 |
60 | /* USER CODE END SPI2_MspInit 0 */
61 | /* SPI2 clock enable */
62 | __HAL_RCC_SPI2_CLK_ENABLE();
63 |
64 | __HAL_RCC_GPIOC_CLK_ENABLE();
65 | __HAL_RCC_GPIOB_CLK_ENABLE();
66 | /**SPI2 GPIO Configuration
67 | PC1 ------> SPI2_MOSI
68 | PC2 ------> SPI2_MISO
69 | PB10 ------> SPI2_SCK
70 | */
71 | GPIO_InitStruct.Pin = Encoder_MOSI_Pin;
72 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
73 | GPIO_InitStruct.Pull = GPIO_NOPULL;
74 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
75 | GPIO_InitStruct.Alternate = GPIO_AF7_SPI2;
76 | HAL_GPIO_Init(Encoder_MOSI_GPIO_Port, &GPIO_InitStruct);
77 |
78 | GPIO_InitStruct.Pin = Encoder_MISO_Pin;
79 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
80 | GPIO_InitStruct.Pull = GPIO_NOPULL;
81 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
82 | GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
83 | HAL_GPIO_Init(Encoder_MISO_GPIO_Port, &GPIO_InitStruct);
84 |
85 | GPIO_InitStruct.Pin = Encoder_SCK_Pin;
86 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
87 | GPIO_InitStruct.Pull = GPIO_NOPULL;
88 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
89 | GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
90 | HAL_GPIO_Init(Encoder_SCK_GPIO_Port, &GPIO_InitStruct);
91 |
92 | /* SPI2 interrupt Init */
93 | HAL_NVIC_SetPriority(SPI2_IRQn, 3, 3);
94 | HAL_NVIC_EnableIRQ(SPI2_IRQn);
95 | /* USER CODE BEGIN SPI2_MspInit 1 */
96 |
97 | /* USER CODE END SPI2_MspInit 1 */
98 | }
99 | }
100 |
101 | void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle)
102 | {
103 |
104 | if(spiHandle->Instance==SPI2)
105 | {
106 | /* USER CODE BEGIN SPI2_MspDeInit 0 */
107 |
108 | /* USER CODE END SPI2_MspDeInit 0 */
109 | /* Peripheral clock disable */
110 | __HAL_RCC_SPI2_CLK_DISABLE();
111 |
112 | /**SPI2 GPIO Configuration
113 | PC1 ------> SPI2_MOSI
114 | PC2 ------> SPI2_MISO
115 | PB10 ------> SPI2_SCK
116 | */
117 | HAL_GPIO_DeInit(GPIOC, Encoder_MOSI_Pin|Encoder_MISO_Pin);
118 |
119 | HAL_GPIO_DeInit(Encoder_SCK_GPIO_Port, Encoder_SCK_Pin);
120 |
121 | /* SPI2 interrupt Deinit */
122 | HAL_NVIC_DisableIRQ(SPI2_IRQn);
123 | /* USER CODE BEGIN SPI2_MspDeInit 1 */
124 |
125 | /* USER CODE END SPI2_MspDeInit 1 */
126 | }
127 | }
128 |
129 | /* USER CODE BEGIN 1 */
130 |
131 | /* USER CODE END 1 */
132 |
133 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
134 |
--------------------------------------------------------------------------------
/Core/Src/stm32f4xx_hal_msp.c:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * File Name : stm32f4xx_hal_msp.c
5 | * Description : This file provides code for the MSP Initialization
6 | * and de-Initialization codes.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2020 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 | /* USER CODE END Header */
21 |
22 | /* Includes ------------------------------------------------------------------*/
23 | #include "main.h"
24 | /* USER CODE BEGIN Includes */
25 |
26 | /* USER CODE END Includes */
27 |
28 | /* Private typedef -----------------------------------------------------------*/
29 | /* USER CODE BEGIN TD */
30 |
31 | /* USER CODE END TD */
32 |
33 | /* Private define ------------------------------------------------------------*/
34 | /* USER CODE BEGIN Define */
35 |
36 | /* USER CODE END Define */
37 |
38 | /* Private macro -------------------------------------------------------------*/
39 | /* USER CODE BEGIN Macro */
40 |
41 | /* USER CODE END Macro */
42 |
43 | /* Private variables ---------------------------------------------------------*/
44 | /* USER CODE BEGIN PV */
45 |
46 | /* USER CODE END PV */
47 |
48 | /* Private function prototypes -----------------------------------------------*/
49 | /* USER CODE BEGIN PFP */
50 |
51 | /* USER CODE END PFP */
52 |
53 | /* External functions --------------------------------------------------------*/
54 | /* USER CODE BEGIN ExternalFunctions */
55 |
56 | /* USER CODE END ExternalFunctions */
57 |
58 | /* USER CODE BEGIN 0 */
59 |
60 | /* USER CODE END 0 */
61 | /**
62 | * Initializes the Global MSP.
63 | */
64 | void HAL_MspInit(void)
65 | {
66 | /* USER CODE BEGIN MspInit 0 */
67 |
68 | /* USER CODE END MspInit 0 */
69 |
70 | __HAL_RCC_SYSCFG_CLK_ENABLE();
71 | __HAL_RCC_PWR_CLK_ENABLE();
72 |
73 | HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_2);
74 |
75 | /* System interrupt init*/
76 |
77 | /* USER CODE BEGIN MspInit 1 */
78 |
79 | /* USER CODE END MspInit 1 */
80 | }
81 |
82 | /* USER CODE BEGIN 1 */
83 |
84 | /* USER CODE END 1 */
85 |
86 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
87 |
--------------------------------------------------------------------------------
/Core/Src/stm32f4xx_it.c:
--------------------------------------------------------------------------------
1 | /* USER CODE BEGIN Header */
2 | /**
3 | ******************************************************************************
4 | * @file stm32f4xx_it.c
5 | * @brief Interrupt Service Routines.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 | /* USER CODE END Header */
20 |
21 | /* Includes ------------------------------------------------------------------*/
22 | #include "main.h"
23 | #include "stm32f4xx_it.h"
24 | /* Private includes ----------------------------------------------------------*/
25 | /* USER CODE BEGIN Includes */
26 | /* USER CODE END Includes */
27 |
28 | /* Private typedef -----------------------------------------------------------*/
29 | /* USER CODE BEGIN TD */
30 |
31 | /* USER CODE END TD */
32 |
33 | /* Private define ------------------------------------------------------------*/
34 | /* USER CODE BEGIN PD */
35 |
36 | /* USER CODE END PD */
37 |
38 | /* Private macro -------------------------------------------------------------*/
39 | /* USER CODE BEGIN PM */
40 |
41 | /* USER CODE END PM */
42 |
43 | /* Private variables ---------------------------------------------------------*/
44 | /* USER CODE BEGIN PV */
45 |
46 | /* USER CODE END PV */
47 |
48 | /* Private function prototypes -----------------------------------------------*/
49 | /* USER CODE BEGIN PFP */
50 |
51 | /* USER CODE END PFP */
52 |
53 | /* Private user code ---------------------------------------------------------*/
54 | /* USER CODE BEGIN 0 */
55 |
56 | /* USER CODE END 0 */
57 |
58 | /* External variables --------------------------------------------------------*/
59 | extern SPI_HandleTypeDef hspi2;
60 | extern TIM_HandleTypeDef htim1;
61 | extern TIM_HandleTypeDef htim8;
62 | extern DMA_HandleTypeDef hdma_usart2_rx;
63 | extern UART_HandleTypeDef huart2;
64 | /* USER CODE BEGIN EV */
65 |
66 | /* USER CODE END EV */
67 |
68 | /******************************************************************************/
69 | /* Cortex-M4 Processor Interruption and Exception Handlers */
70 | /******************************************************************************/
71 | /**
72 | * @brief This function handles Non maskable interrupt.
73 | */
74 | void NMI_Handler(void)
75 | {
76 | /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
77 |
78 | /* USER CODE END NonMaskableInt_IRQn 0 */
79 | /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
80 |
81 | /* USER CODE END NonMaskableInt_IRQn 1 */
82 | }
83 |
84 | /**
85 | * @brief This function handles Hard fault interrupt.
86 | */
87 | void HardFault_Handler(void)
88 | {
89 | /* USER CODE BEGIN HardFault_IRQn 0 */
90 |
91 | /* USER CODE END HardFault_IRQn 0 */
92 | while (1)
93 | {
94 | /* USER CODE BEGIN W1_HardFault_IRQn 0 */
95 | /* USER CODE END W1_HardFault_IRQn 0 */
96 | }
97 | }
98 |
99 | /**
100 | * @brief This function handles Memory management fault.
101 | */
102 | void MemManage_Handler(void)
103 | {
104 | /* USER CODE BEGIN MemoryManagement_IRQn 0 */
105 |
106 | /* USER CODE END MemoryManagement_IRQn 0 */
107 | while (1)
108 | {
109 | /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */
110 | /* USER CODE END W1_MemoryManagement_IRQn 0 */
111 | }
112 | }
113 |
114 | /**
115 | * @brief This function handles Pre-fetch fault, memory access fault.
116 | */
117 | void BusFault_Handler(void)
118 | {
119 | /* USER CODE BEGIN BusFault_IRQn 0 */
120 |
121 | /* USER CODE END BusFault_IRQn 0 */
122 | while (1)
123 | {
124 | /* USER CODE BEGIN W1_BusFault_IRQn 0 */
125 | /* USER CODE END W1_BusFault_IRQn 0 */
126 | }
127 | }
128 |
129 | /**
130 | * @brief This function handles Undefined instruction or illegal state.
131 | */
132 | void UsageFault_Handler(void)
133 | {
134 | /* USER CODE BEGIN UsageFault_IRQn 0 */
135 |
136 | /* USER CODE END UsageFault_IRQn 0 */
137 | while (1)
138 | {
139 | /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
140 | /* USER CODE END W1_UsageFault_IRQn 0 */
141 | }
142 | }
143 |
144 | /**
145 | * @brief This function handles System service call via SWI instruction.
146 | */
147 | void SVC_Handler(void)
148 | {
149 | /* USER CODE BEGIN SVCall_IRQn 0 */
150 |
151 | /* USER CODE END SVCall_IRQn 0 */
152 | /* USER CODE BEGIN SVCall_IRQn 1 */
153 |
154 | /* USER CODE END SVCall_IRQn 1 */
155 | }
156 |
157 | /**
158 | * @brief This function handles Debug monitor.
159 | */
160 | void DebugMon_Handler(void)
161 | {
162 | /* USER CODE BEGIN DebugMonitor_IRQn 0 */
163 |
164 | /* USER CODE END DebugMonitor_IRQn 0 */
165 | /* USER CODE BEGIN DebugMonitor_IRQn 1 */
166 |
167 | /* USER CODE END DebugMonitor_IRQn 1 */
168 | }
169 |
170 | /**
171 | * @brief This function handles Pendable request for system service.
172 | */
173 | void PendSV_Handler(void)
174 | {
175 | /* USER CODE BEGIN PendSV_IRQn 0 */
176 |
177 | /* USER CODE END PendSV_IRQn 0 */
178 | /* USER CODE BEGIN PendSV_IRQn 1 */
179 |
180 | /* USER CODE END PendSV_IRQn 1 */
181 | }
182 |
183 | /**
184 | * @brief This function handles System tick timer.
185 | */
186 | void SysTick_Handler(void)
187 | {
188 | /* USER CODE BEGIN SysTick_IRQn 0 */
189 |
190 | /* USER CODE END SysTick_IRQn 0 */
191 | HAL_IncTick();
192 | /* USER CODE BEGIN SysTick_IRQn 1 */
193 |
194 | /* USER CODE END SysTick_IRQn 1 */
195 | }
196 |
197 | /******************************************************************************/
198 | /* STM32F4xx Peripheral Interrupt Handlers */
199 | /* Add here the Interrupt Handlers for the used peripherals. */
200 | /* For the available peripheral interrupt handler names, */
201 | /* please refer to the startup file (startup_stm32f4xx.s). */
202 | /******************************************************************************/
203 |
204 | /**
205 | * @brief This function handles DMA1 stream5 global interrupt.
206 | */
207 | void DMA1_Stream5_IRQHandler(void)
208 | {
209 | /* USER CODE BEGIN DMA1_Stream5_IRQn 0 */
210 |
211 | /* USER CODE END DMA1_Stream5_IRQn 0 */
212 | HAL_DMA_IRQHandler(&hdma_usart2_rx);
213 | /* USER CODE BEGIN DMA1_Stream5_IRQn 1 */
214 |
215 | /* USER CODE END DMA1_Stream5_IRQn 1 */
216 | }
217 |
218 | /**
219 | * @brief This function handles TIM1 update interrupt and TIM10 global interrupt.
220 | */
221 | void TIM1_UP_TIM10_IRQHandler(void)
222 | {
223 | /* USER CODE BEGIN TIM1_UP_TIM10_IRQn 0 */
224 |
225 | /* USER CODE END TIM1_UP_TIM10_IRQn 0 */
226 | HAL_TIM_IRQHandler(&htim1);
227 | /* USER CODE BEGIN TIM1_UP_TIM10_IRQn 1 */
228 |
229 | /* USER CODE END TIM1_UP_TIM10_IRQn 1 */
230 | }
231 |
232 | /**
233 | * @brief This function handles SPI2 global interrupt.
234 | */
235 | void SPI2_IRQHandler(void)
236 | {
237 | /* USER CODE BEGIN SPI2_IRQn 0 */
238 |
239 | /* USER CODE END SPI2_IRQn 0 */
240 | HAL_SPI_IRQHandler(&hspi2);
241 | /* USER CODE BEGIN SPI2_IRQn 1 */
242 |
243 | /* USER CODE END SPI2_IRQn 1 */
244 | }
245 |
246 | /**
247 | * @brief This function handles USART2 global interrupt.
248 | */
249 | void USART2_IRQHandler(void)
250 | {
251 | /* USER CODE BEGIN USART2_IRQn 0 */
252 |
253 | /* USER CODE END USART2_IRQn 0 */
254 | HAL_UART_IRQHandler(&huart2);
255 | /* USER CODE BEGIN USART2_IRQn 1 */
256 |
257 | /* USER CODE END USART2_IRQn 1 */
258 | }
259 |
260 | /**
261 | * @brief This function handles TIM8 update interrupt and TIM13 global interrupt.
262 | */
263 | void TIM8_UP_TIM13_IRQHandler(void)
264 | {
265 | /* USER CODE BEGIN TIM8_UP_TIM13_IRQn 0 */
266 |
267 | /* USER CODE END TIM8_UP_TIM13_IRQn 0 */
268 | HAL_TIM_IRQHandler(&htim8);
269 | /* USER CODE BEGIN TIM8_UP_TIM13_IRQn 1 */
270 |
271 | /* USER CODE END TIM8_UP_TIM13_IRQn 1 */
272 | }
273 |
274 | /* USER CODE BEGIN 1 */
275 |
276 | /* USER CODE END 1 */
277 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
278 |
--------------------------------------------------------------------------------
/Core/Src/syscalls.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file syscalls.c
4 | * @author Auto-generated by STM32CubeIDE
5 | * @brief STM32CubeIDE Minimal System calls file
6 | *
7 | * For more information about which c-functions
8 | * need which of these lowlevel functions
9 | * please consult the Newlib libc-manual
10 | ******************************************************************************
11 | * @attention
12 | *
13 | * © Copyright (c) 2020 STMicroelectronics.
14 | * All rights reserved.
15 | *
16 | * This software component is licensed by ST under BSD 3-Clause license,
17 | * the "License"; You may not use this file except in compliance with the
18 | * License. You may obtain a copy of the License at:
19 | * opensource.org/licenses/BSD-3-Clause
20 | *
21 | ******************************************************************************
22 | */
23 |
24 | /* Includes */
25 | #include
26 | #include
27 | #include
28 | #include
29 | #include
30 | #include
31 | #include
32 | #include
33 |
34 |
35 | /* Variables */
36 | //#undef errno
37 | extern int errno;
38 | extern int __io_putchar(int ch) __attribute__((weak));
39 | extern int __io_getchar(void) __attribute__((weak));
40 |
41 | register char * stack_ptr asm("sp");
42 |
43 | char *__env[1] = { 0 };
44 | char **environ = __env;
45 |
46 |
47 | /* Functions */
48 | void initialise_monitor_handles()
49 | {
50 | }
51 |
52 | int _getpid(void)
53 | {
54 | return 1;
55 | }
56 |
57 | int _kill(int pid, int sig)
58 | {
59 | errno = EINVAL;
60 | return -1;
61 | }
62 |
63 | void _exit (int status)
64 | {
65 | _kill(status, -1);
66 | while (1) {} /* Make sure we hang here */
67 | }
68 |
69 | __attribute__((weak)) int _read(int file, char *ptr, int len)
70 | {
71 | int DataIdx;
72 |
73 | for (DataIdx = 0; DataIdx < len; DataIdx++)
74 | {
75 | *ptr++ = __io_getchar();
76 | }
77 |
78 | return len;
79 | }
80 |
81 | __attribute__((weak)) int _write(int file, char *ptr, int len)
82 | {
83 | int DataIdx;
84 |
85 | for (DataIdx = 0; DataIdx < len; DataIdx++)
86 | {
87 | __io_putchar(*ptr++);
88 | }
89 | return len;
90 | }
91 |
92 | int _close(int file)
93 | {
94 | return -1;
95 | }
96 |
97 |
98 | int _fstat(int file, struct stat *st)
99 | {
100 | st->st_mode = S_IFCHR;
101 | return 0;
102 | }
103 |
104 | int _isatty(int file)
105 | {
106 | return 1;
107 | }
108 |
109 | int _lseek(int file, int ptr, int dir)
110 | {
111 | return 0;
112 | }
113 |
114 | int _open(char *path, int flags, ...)
115 | {
116 | /* Pretend like we always fail */
117 | return -1;
118 | }
119 |
120 | int _wait(int *status)
121 | {
122 | errno = ECHILD;
123 | return -1;
124 | }
125 |
126 | int _unlink(char *name)
127 | {
128 | errno = ENOENT;
129 | return -1;
130 | }
131 |
132 | int _times(struct tms *buf)
133 | {
134 | return -1;
135 | }
136 |
137 | int _stat(char *file, struct stat *st)
138 | {
139 | st->st_mode = S_IFCHR;
140 | return 0;
141 | }
142 |
143 | int _link(char *old, char *new)
144 | {
145 | errno = EMLINK;
146 | return -1;
147 | }
148 |
149 | int _fork(void)
150 | {
151 | errno = EAGAIN;
152 | return -1;
153 | }
154 |
155 | int _execve(char *name, char **argv, char **env)
156 | {
157 | errno = ENOMEM;
158 | return -1;
159 | }
160 |
--------------------------------------------------------------------------------
/Core/Src/sysmem.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file sysmem.c
4 | * @author Generated by STM32CubeIDE
5 | * @brief STM32CubeIDE System Memory calls file
6 | *
7 | * For more information about which C functions
8 | * need which of these lowlevel functions
9 | * please consult the newlib libc manual
10 | ******************************************************************************
11 | * @attention
12 | *
13 | * © Copyright (c) 2020 STMicroelectronics.
14 | * All rights reserved.
15 | *
16 | * This software component is licensed by ST under BSD 3-Clause license,
17 | * the "License"; You may not use this file except in compliance with the
18 | * License. You may obtain a copy of the License at:
19 | * opensource.org/licenses/BSD-3-Clause
20 | *
21 | ******************************************************************************
22 | */
23 |
24 | /* Includes */
25 | #include
26 | #include
27 |
28 | /**
29 | * Pointer to the current high watermark of the heap usage
30 | */
31 | static uint8_t *__sbrk_heap_end = NULL;
32 |
33 | /**
34 | * @brief _sbrk() allocates memory to the newlib heap and is used by malloc
35 | * and others from the C library
36 | *
37 | * @verbatim
38 | * ############################################################################
39 | * # .data # .bss # newlib heap # MSP stack #
40 | * # # # # Reserved by _Min_Stack_Size #
41 | * ############################################################################
42 | * ^-- RAM start ^-- _end _estack, RAM end --^
43 | * @endverbatim
44 | *
45 | * This implementation starts allocating at the '_end' linker symbol
46 | * The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack
47 | * The implementation considers '_estack' linker symbol to be RAM end
48 | * NOTE: If the MSP stack, at any point during execution, grows larger than the
49 | * reserved size, please increase the '_Min_Stack_Size'.
50 | *
51 | * @param incr Memory size
52 | * @return Pointer to allocated memory
53 | */
54 | void *_sbrk(ptrdiff_t incr)
55 | {
56 | extern uint8_t _end; /* Symbol defined in the linker script */
57 | extern uint8_t _estack; /* Symbol defined in the linker script */
58 | extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */
59 | const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size;
60 | const uint8_t *max_heap = (uint8_t *)stack_limit;
61 | uint8_t *prev_heap_end;
62 |
63 | /* Initalize heap end at first call */
64 | if (NULL == __sbrk_heap_end)
65 | {
66 | __sbrk_heap_end = &_end;
67 | }
68 |
69 | /* Protect heap from growing into the reserved MSP stack */
70 | if (__sbrk_heap_end + incr > max_heap)
71 | {
72 | errno = ENOMEM;
73 | return (void *)-1;
74 | }
75 |
76 | prev_heap_end = __sbrk_heap_end;
77 | __sbrk_heap_end += incr;
78 |
79 | return (void *)prev_heap_end;
80 | }
81 |
--------------------------------------------------------------------------------
/Core/Src/tim.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : TIM.c
4 | * Description : This file provides code for the configuration
5 | * of the TIM instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "tim.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | TIM_HandleTypeDef htim1;
28 | TIM_HandleTypeDef htim2;
29 | TIM_HandleTypeDef htim8;
30 |
31 | /* TIM1 init function */
32 | void MX_TIM1_Init(void)
33 | {
34 | TIM_ClockConfigTypeDef sClockSourceConfig = {0};
35 | TIM_MasterConfigTypeDef sMasterConfig = {0};
36 | TIM_OC_InitTypeDef sConfigOC = {0};
37 | TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
38 |
39 | htim1.Instance = TIM1;
40 | htim1.Init.Prescaler = 0;
41 | htim1.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED2;
42 | htim1.Init.Period = 0xfff;
43 | htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
44 | htim1.Init.RepetitionCounter = 1;
45 | htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
46 | if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
47 | {
48 | Error_Handler();
49 | }
50 | sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
51 | if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK)
52 | {
53 | Error_Handler();
54 | }
55 | if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
56 | {
57 | Error_Handler();
58 | }
59 | sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
60 | sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
61 | if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
62 | {
63 | Error_Handler();
64 | }
65 | sConfigOC.OCMode = TIM_OCMODE_PWM1;
66 | sConfigOC.Pulse = 0;
67 | sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
68 | sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
69 | sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
70 | sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
71 | sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
72 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK)
73 | {
74 | Error_Handler();
75 | }
76 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
77 | {
78 | Error_Handler();
79 | }
80 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
81 | {
82 | Error_Handler();
83 | }
84 | sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
85 | sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
86 | sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
87 | sBreakDeadTimeConfig.DeadTime = DEADTIME_CLK;
88 | sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
89 | sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
90 | sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
91 | if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
92 | {
93 | Error_Handler();
94 | }
95 | HAL_TIM_MspPostInit(&htim1);
96 |
97 | }
98 | /* TIM2 init function */
99 | void MX_TIM2_Init(void)
100 | {
101 | TIM_ClockConfigTypeDef sClockSourceConfig = {0};
102 | TIM_MasterConfigTypeDef sMasterConfig = {0};
103 | TIM_OC_InitTypeDef sConfigOC = {0};
104 |
105 | htim2.Instance = TIM2;
106 | htim2.Init.Prescaler = 0;
107 | htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
108 | htim2.Init.Period = 0xfff;
109 | htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
110 | htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
111 | if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
112 | {
113 | Error_Handler();
114 | }
115 | sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
116 | if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
117 | {
118 | Error_Handler();
119 | }
120 | if (HAL_TIM_PWM_Init(&htim2) != HAL_OK)
121 | {
122 | Error_Handler();
123 | }
124 | sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
125 | sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
126 | if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
127 | {
128 | Error_Handler();
129 | }
130 | sConfigOC.OCMode = TIM_OCMODE_PWM1;
131 | sConfigOC.Pulse = 0;
132 | sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
133 | sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
134 | if (HAL_TIM_PWM_ConfigChannel(&htim2, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
135 | {
136 | Error_Handler();
137 | }
138 | HAL_TIM_MspPostInit(&htim2);
139 |
140 | }
141 | /* TIM8 init function */
142 | void MX_TIM8_Init(void)
143 | {
144 | TIM_ClockConfigTypeDef sClockSourceConfig = {0};
145 | TIM_MasterConfigTypeDef sMasterConfig = {0};
146 |
147 | htim8.Instance = TIM8;
148 | htim8.Init.Prescaler = 0;
149 | htim8.Init.CounterMode = TIM_COUNTERMODE_UP;
150 | htim8.Init.Period = 0xfff;
151 | htim8.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
152 | htim8.Init.RepetitionCounter = 0;
153 | htim8.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
154 | if (HAL_TIM_Base_Init(&htim8) != HAL_OK)
155 | {
156 | Error_Handler();
157 | }
158 | sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
159 | if (HAL_TIM_ConfigClockSource(&htim8, &sClockSourceConfig) != HAL_OK)
160 | {
161 | Error_Handler();
162 | }
163 | sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE;
164 | sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_ENABLE;
165 | if (HAL_TIMEx_MasterConfigSynchronization(&htim8, &sMasterConfig) != HAL_OK)
166 | {
167 | Error_Handler();
168 | }
169 |
170 | }
171 |
172 | void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
173 | {
174 |
175 | if(tim_baseHandle->Instance==TIM1)
176 | {
177 | /* USER CODE BEGIN TIM1_MspInit 0 */
178 |
179 | /* USER CODE END TIM1_MspInit 0 */
180 | /* TIM1 clock enable */
181 | __HAL_RCC_TIM1_CLK_ENABLE();
182 |
183 | /* TIM1 interrupt Init */
184 | HAL_NVIC_SetPriority(TIM1_UP_TIM10_IRQn, 1, 1);
185 | HAL_NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn);
186 | /* USER CODE BEGIN TIM1_MspInit 1 */
187 |
188 | /* USER CODE END TIM1_MspInit 1 */
189 | }
190 | else if(tim_baseHandle->Instance==TIM2)
191 | {
192 | /* USER CODE BEGIN TIM2_MspInit 0 */
193 |
194 | /* USER CODE END TIM2_MspInit 0 */
195 | /* TIM2 clock enable */
196 | __HAL_RCC_TIM2_CLK_ENABLE();
197 | /* USER CODE BEGIN TIM2_MspInit 1 */
198 |
199 | /* USER CODE END TIM2_MspInit 1 */
200 | }
201 | else if(tim_baseHandle->Instance==TIM8)
202 | {
203 | /* USER CODE BEGIN TIM8_MspInit 0 */
204 |
205 | /* USER CODE END TIM8_MspInit 0 */
206 | /* TIM8 clock enable */
207 | __HAL_RCC_TIM8_CLK_ENABLE();
208 |
209 | /* TIM8 interrupt Init */
210 | HAL_NVIC_SetPriority(TIM8_UP_TIM13_IRQn, 1, 1);
211 | HAL_NVIC_EnableIRQ(TIM8_UP_TIM13_IRQn);
212 | /* USER CODE BEGIN TIM8_MspInit 1 */
213 |
214 | /* USER CODE END TIM8_MspInit 1 */
215 | }
216 | }
217 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
218 | {
219 |
220 | GPIO_InitTypeDef GPIO_InitStruct = {0};
221 | if(timHandle->Instance==TIM1)
222 | {
223 | /* USER CODE BEGIN TIM1_MspPostInit 0 */
224 |
225 | /* USER CODE END TIM1_MspPostInit 0 */
226 | __HAL_RCC_GPIOA_CLK_ENABLE();
227 | __HAL_RCC_GPIOB_CLK_ENABLE();
228 | /**TIM1 GPIO Configuration
229 | PA7 ------> TIM1_CH1N
230 | PB0 ------> TIM1_CH2N
231 | PB1 ------> TIM1_CH3N
232 | PA8 ------> TIM1_CH1
233 | PA9 ------> TIM1_CH2
234 | PA10 ------> TIM1_CH3
235 | */
236 | GPIO_InitStruct.Pin = AL_Pin|AH_Pin|BH_Pin|CH_Pin;
237 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
238 | GPIO_InitStruct.Pull = GPIO_NOPULL;
239 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
240 | GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
241 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
242 |
243 | GPIO_InitStruct.Pin = BL_Pin|CL_Pin;
244 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
245 | GPIO_InitStruct.Pull = GPIO_NOPULL;
246 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
247 | GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
248 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
249 |
250 | /* USER CODE BEGIN TIM1_MspPostInit 1 */
251 |
252 | /* USER CODE END TIM1_MspPostInit 1 */
253 | }
254 | else if(timHandle->Instance==TIM2)
255 | {
256 | /* USER CODE BEGIN TIM2_MspPostInit 0 */
257 |
258 | /* USER CODE END TIM2_MspPostInit 0 */
259 |
260 | __HAL_RCC_GPIOB_CLK_ENABLE();
261 | /**TIM2 GPIO Configuration
262 | PB2 ------> TIM2_CH4
263 | */
264 | GPIO_InitStruct.Pin = LED_Pin;
265 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
266 | GPIO_InitStruct.Pull = GPIO_NOPULL;
267 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
268 | GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
269 | HAL_GPIO_Init(LED_GPIO_Port, &GPIO_InitStruct);
270 |
271 | /* USER CODE BEGIN TIM2_MspPostInit 1 */
272 |
273 | /* USER CODE END TIM2_MspPostInit 1 */
274 | }
275 |
276 | }
277 |
278 | void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
279 | {
280 |
281 | if(tim_baseHandle->Instance==TIM1)
282 | {
283 | /* USER CODE BEGIN TIM1_MspDeInit 0 */
284 |
285 | /* USER CODE END TIM1_MspDeInit 0 */
286 | /* Peripheral clock disable */
287 | __HAL_RCC_TIM1_CLK_DISABLE();
288 |
289 | /* TIM1 interrupt Deinit */
290 | HAL_NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn);
291 | /* USER CODE BEGIN TIM1_MspDeInit 1 */
292 |
293 | /* USER CODE END TIM1_MspDeInit 1 */
294 | }
295 | else if(tim_baseHandle->Instance==TIM2)
296 | {
297 | /* USER CODE BEGIN TIM2_MspDeInit 0 */
298 |
299 | /* USER CODE END TIM2_MspDeInit 0 */
300 | /* Peripheral clock disable */
301 | __HAL_RCC_TIM2_CLK_DISABLE();
302 | /* USER CODE BEGIN TIM2_MspDeInit 1 */
303 |
304 | /* USER CODE END TIM2_MspDeInit 1 */
305 | }
306 | else if(tim_baseHandle->Instance==TIM8)
307 | {
308 | /* USER CODE BEGIN TIM8_MspDeInit 0 */
309 |
310 | /* USER CODE END TIM8_MspDeInit 0 */
311 | /* Peripheral clock disable */
312 | __HAL_RCC_TIM8_CLK_DISABLE();
313 |
314 | /* TIM8 interrupt Deinit */
315 | HAL_NVIC_DisableIRQ(TIM8_UP_TIM13_IRQn);
316 | /* USER CODE BEGIN TIM8_MspDeInit 1 */
317 |
318 | /* USER CODE END TIM8_MspDeInit 1 */
319 | }
320 | }
321 |
322 | /* USER CODE BEGIN 1 */
323 |
324 | /* USER CODE END 1 */
325 |
326 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
327 |
--------------------------------------------------------------------------------
/Core/Src/usart.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * File Name : USART.c
4 | * Description : This file provides code for the configuration
5 | * of the USART instances.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2020 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Includes ------------------------------------------------------------------*/
21 | #include "usart.h"
22 |
23 | /* USER CODE BEGIN 0 */
24 |
25 | /* USER CODE END 0 */
26 |
27 | UART_HandleTypeDef huart2;
28 | DMA_HandleTypeDef hdma_usart2_rx;
29 |
30 | /* USART2 init function */
31 |
32 | void MX_USART2_UART_Init(void)
33 | {
34 |
35 | huart2.Instance = USART2;
36 | huart2.Init.BaudRate = 1000000;
37 | huart2.Init.WordLength = UART_WORDLENGTH_8B;
38 | huart2.Init.StopBits = UART_STOPBITS_1;
39 | huart2.Init.Parity = UART_PARITY_NONE;
40 | huart2.Init.Mode = UART_MODE_TX_RX;
41 | huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
42 | huart2.Init.OverSampling = UART_OVERSAMPLING_16;
43 | if (HAL_UART_Init(&huart2) != HAL_OK)
44 | {
45 | Error_Handler();
46 | }
47 |
48 | }
49 |
50 | void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
51 | {
52 |
53 | GPIO_InitTypeDef GPIO_InitStruct = {0};
54 | if(uartHandle->Instance==USART2)
55 | {
56 | /* USER CODE BEGIN USART2_MspInit 0 */
57 |
58 | /* USER CODE END USART2_MspInit 0 */
59 | /* USART2 clock enable */
60 | __HAL_RCC_USART2_CLK_ENABLE();
61 |
62 | __HAL_RCC_GPIOA_CLK_ENABLE();
63 | /**USART2 GPIO Configuration
64 | PA2 ------> USART2_TX
65 | PA3 ------> USART2_RX
66 | */
67 | GPIO_InitStruct.Pin = ControlBus_TX_Pin|ControlBus_RX_Pin;
68 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
69 | GPIO_InitStruct.Pull = GPIO_PULLUP;
70 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
71 | GPIO_InitStruct.Alternate = GPIO_AF7_USART2;
72 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
73 |
74 | /* USART2 DMA Init */
75 | /* USART2_RX Init */
76 | hdma_usart2_rx.Instance = DMA1_Stream5;
77 | hdma_usart2_rx.Init.Channel = DMA_CHANNEL_4;
78 | hdma_usart2_rx.Init.Direction = DMA_PERIPH_TO_MEMORY;
79 | hdma_usart2_rx.Init.PeriphInc = DMA_PINC_DISABLE;
80 | hdma_usart2_rx.Init.MemInc = DMA_MINC_ENABLE;
81 | hdma_usart2_rx.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
82 | hdma_usart2_rx.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
83 | hdma_usart2_rx.Init.Mode = DMA_CIRCULAR;
84 | hdma_usart2_rx.Init.Priority = DMA_PRIORITY_LOW;
85 | hdma_usart2_rx.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
86 | if (HAL_DMA_Init(&hdma_usart2_rx) != HAL_OK)
87 | {
88 | Error_Handler();
89 | }
90 |
91 | __HAL_LINKDMA(uartHandle,hdmarx,hdma_usart2_rx);
92 |
93 | /* USART2 interrupt Init */
94 | HAL_NVIC_SetPriority(USART2_IRQn, 1, 1);
95 | HAL_NVIC_EnableIRQ(USART2_IRQn);
96 | /* USER CODE BEGIN USART2_MspInit 1 */
97 |
98 | /* USER CODE END USART2_MspInit 1 */
99 | }
100 | }
101 |
102 | void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle)
103 | {
104 |
105 | if(uartHandle->Instance==USART2)
106 | {
107 | /* USER CODE BEGIN USART2_MspDeInit 0 */
108 |
109 | /* USER CODE END USART2_MspDeInit 0 */
110 | /* Peripheral clock disable */
111 | __HAL_RCC_USART2_CLK_DISABLE();
112 |
113 | /**USART2 GPIO Configuration
114 | PA2 ------> USART2_TX
115 | PA3 ------> USART2_RX
116 | */
117 | HAL_GPIO_DeInit(GPIOA, ControlBus_TX_Pin|ControlBus_RX_Pin);
118 |
119 | /* USART2 DMA DeInit */
120 | HAL_DMA_DeInit(uartHandle->hdmarx);
121 |
122 | /* USART2 interrupt Deinit */
123 | HAL_NVIC_DisableIRQ(USART2_IRQn);
124 | /* USER CODE BEGIN USART2_MspDeInit 1 */
125 |
126 | /* USER CODE END USART2_MspDeInit 1 */
127 | }
128 | }
129 |
130 | /* USER CODE BEGIN 1 */
131 |
132 | /* USER CODE END 1 */
133 |
134 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
135 |
--------------------------------------------------------------------------------
/DigitalFilter/lowpass.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | void LowPass::SetParam(float cutOffFreq, float delta)
4 | {
5 | e = 1.0f - exp(-delta * 2.0f * (float) M_PI * cutOffFreq);
6 | }
7 |
8 | float LowPass::Update(float input)
9 | {
10 | output += (input - output) * e;
11 |
12 | return output;
13 | }
14 |
--------------------------------------------------------------------------------
/DigitalFilter/lowpass.hpp:
--------------------------------------------------------------------------------
1 | #ifndef LOWPASS_HPP_
2 | #define LOWPASS_HPP_
3 |
4 | #include
5 |
6 | class LowPass
7 | {
8 | public:
9 | void SetParam(float cutOffFreq, float delta);
10 | float Update(float input);
11 |
12 | private:
13 | float e;
14 | float output = 0.0f;
15 | };
16 |
17 | #endif
18 |
--------------------------------------------------------------------------------
/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/jwkim04/J-Drive/d0f84098e73e7f731cb00cbc4d384b8ab88578d9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h
--------------------------------------------------------------------------------
/Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file system_stm32f4xx.h
4 | * @author MCD Application Team
5 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © COPYRIGHT(c) 2017 STMicroelectronics
10 | *
11 | * Redistribution and use in source and binary forms, with or without modification,
12 | * are permitted provided that the following conditions are met:
13 | * 1. Redistributions of source code must retain the above copyright notice,
14 | * this list of conditions and the following disclaimer.
15 | * 2. Redistributions in binary form must reproduce the above copyright notice,
16 | * this list of conditions and the following disclaimer in the documentation
17 | * and/or other materials provided with the distribution.
18 | * 3. Neither the name of STMicroelectronics nor the names of its contributors
19 | * may be used to endorse or promote products derived from this software
20 | * without specific prior written permission.
21 | *
22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
23 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
24 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
25 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 | *
33 | ******************************************************************************
34 | */
35 |
36 | /** @addtogroup CMSIS
37 | * @{
38 | */
39 |
40 | /** @addtogroup stm32f4xx_system
41 | * @{
42 | */
43 |
44 | /**
45 | * @brief Define to prevent recursive inclusion
46 | */
47 | #ifndef __SYSTEM_STM32F4XX_H
48 | #define __SYSTEM_STM32F4XX_H
49 |
50 | #ifdef __cplusplus
51 | extern "C" {
52 | #endif
53 |
54 | /** @addtogroup STM32F4xx_System_Includes
55 | * @{
56 | */
57 |
58 | /**
59 | * @}
60 | */
61 |
62 |
63 | /** @addtogroup STM32F4xx_System_Exported_types
64 | * @{
65 | */
66 | /* This variable is updated in three ways:
67 | 1) by calling CMSIS function SystemCoreClockUpdate()
68 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq()
69 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
70 | Note: If you use this function to configure the system clock; then there
71 | is no need to call the 2 first functions listed above, since SystemCoreClock
72 | variable is updated automatically.
73 | */
74 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
75 |
76 | extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */
77 | extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */
78 |
79 | /**
80 | * @}
81 | */
82 |
83 | /** @addtogroup STM32F4xx_System_Exported_Constants
84 | * @{
85 | */
86 |
87 | /**
88 | * @}
89 | */
90 |
91 | /** @addtogroup STM32F4xx_System_Exported_Macros
92 | * @{
93 | */
94 |
95 | /**
96 | * @}
97 | */
98 |
99 | /** @addtogroup STM32F4xx_System_Exported_Functions
100 | * @{
101 | */
102 |
103 | extern void SystemInit(void);
104 | extern void SystemCoreClockUpdate(void);
105 | /**
106 | * @}
107 | */
108 |
109 | #ifdef __cplusplus
110 | }
111 | #endif
112 |
113 | #endif /*__SYSTEM_STM32F4XX_H */
114 |
115 | /**
116 | * @}
117 | */
118 |
119 | /**
120 | * @}
121 | */
122 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
123 |
--------------------------------------------------------------------------------
/Drivers/CMSIS/Include/cmsis_compiler.h:
--------------------------------------------------------------------------------
1 | /**************************************************************************//**
2 | * @file cmsis_compiler.h
3 | * @brief CMSIS compiler generic header file
4 | * @version V5.0.4
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2009-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #ifndef __CMSIS_COMPILER_H
26 | #define __CMSIS_COMPILER_H
27 |
28 | #include
29 |
30 | /*
31 | * Arm Compiler 4/5
32 | */
33 | #if defined ( __CC_ARM )
34 | #include "cmsis_armcc.h"
35 |
36 |
37 | /*
38 | * Arm Compiler 6 (armclang)
39 | */
40 | #elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)
41 | #include "cmsis_armclang.h"
42 |
43 |
44 | /*
45 | * GNU Compiler
46 | */
47 | #elif defined ( __GNUC__ )
48 | #include "cmsis_gcc.h"
49 |
50 |
51 | /*
52 | * IAR Compiler
53 | */
54 | #elif defined ( __ICCARM__ )
55 | #include
56 |
57 |
58 | /*
59 | * TI Arm Compiler
60 | */
61 | #elif defined ( __TI_ARM__ )
62 | #include
63 |
64 | #ifndef __ASM
65 | #define __ASM __asm
66 | #endif
67 | #ifndef __INLINE
68 | #define __INLINE inline
69 | #endif
70 | #ifndef __STATIC_INLINE
71 | #define __STATIC_INLINE static inline
72 | #endif
73 | #ifndef __STATIC_FORCEINLINE
74 | #define __STATIC_FORCEINLINE __STATIC_INLINE
75 | #endif
76 | #ifndef __NO_RETURN
77 | #define __NO_RETURN __attribute__((noreturn))
78 | #endif
79 | #ifndef __USED
80 | #define __USED __attribute__((used))
81 | #endif
82 | #ifndef __WEAK
83 | #define __WEAK __attribute__((weak))
84 | #endif
85 | #ifndef __PACKED
86 | #define __PACKED __attribute__((packed))
87 | #endif
88 | #ifndef __PACKED_STRUCT
89 | #define __PACKED_STRUCT struct __attribute__((packed))
90 | #endif
91 | #ifndef __PACKED_UNION
92 | #define __PACKED_UNION union __attribute__((packed))
93 | #endif
94 | #ifndef __UNALIGNED_UINT32 /* deprecated */
95 | struct __attribute__((packed)) T_UINT32 { uint32_t v; };
96 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
97 | #endif
98 | #ifndef __UNALIGNED_UINT16_WRITE
99 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
100 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val))
101 | #endif
102 | #ifndef __UNALIGNED_UINT16_READ
103 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
104 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
105 | #endif
106 | #ifndef __UNALIGNED_UINT32_WRITE
107 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
108 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
109 | #endif
110 | #ifndef __UNALIGNED_UINT32_READ
111 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
112 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
113 | #endif
114 | #ifndef __ALIGNED
115 | #define __ALIGNED(x) __attribute__((aligned(x)))
116 | #endif
117 | #ifndef __RESTRICT
118 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
119 | #define __RESTRICT
120 | #endif
121 |
122 |
123 | /*
124 | * TASKING Compiler
125 | */
126 | #elif defined ( __TASKING__ )
127 | /*
128 | * The CMSIS functions have been implemented as intrinsics in the compiler.
129 | * Please use "carm -?i" to get an up to date list of all intrinsics,
130 | * Including the CMSIS ones.
131 | */
132 |
133 | #ifndef __ASM
134 | #define __ASM __asm
135 | #endif
136 | #ifndef __INLINE
137 | #define __INLINE inline
138 | #endif
139 | #ifndef __STATIC_INLINE
140 | #define __STATIC_INLINE static inline
141 | #endif
142 | #ifndef __STATIC_FORCEINLINE
143 | #define __STATIC_FORCEINLINE __STATIC_INLINE
144 | #endif
145 | #ifndef __NO_RETURN
146 | #define __NO_RETURN __attribute__((noreturn))
147 | #endif
148 | #ifndef __USED
149 | #define __USED __attribute__((used))
150 | #endif
151 | #ifndef __WEAK
152 | #define __WEAK __attribute__((weak))
153 | #endif
154 | #ifndef __PACKED
155 | #define __PACKED __packed__
156 | #endif
157 | #ifndef __PACKED_STRUCT
158 | #define __PACKED_STRUCT struct __packed__
159 | #endif
160 | #ifndef __PACKED_UNION
161 | #define __PACKED_UNION union __packed__
162 | #endif
163 | #ifndef __UNALIGNED_UINT32 /* deprecated */
164 | struct __packed__ T_UINT32 { uint32_t v; };
165 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
166 | #endif
167 | #ifndef __UNALIGNED_UINT16_WRITE
168 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
169 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
170 | #endif
171 | #ifndef __UNALIGNED_UINT16_READ
172 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
173 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
174 | #endif
175 | #ifndef __UNALIGNED_UINT32_WRITE
176 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
177 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
178 | #endif
179 | #ifndef __UNALIGNED_UINT32_READ
180 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
181 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
182 | #endif
183 | #ifndef __ALIGNED
184 | #define __ALIGNED(x) __align(x)
185 | #endif
186 | #ifndef __RESTRICT
187 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
188 | #define __RESTRICT
189 | #endif
190 |
191 |
192 | /*
193 | * COSMIC Compiler
194 | */
195 | #elif defined ( __CSMC__ )
196 | #include
197 |
198 | #ifndef __ASM
199 | #define __ASM _asm
200 | #endif
201 | #ifndef __INLINE
202 | #define __INLINE inline
203 | #endif
204 | #ifndef __STATIC_INLINE
205 | #define __STATIC_INLINE static inline
206 | #endif
207 | #ifndef __STATIC_FORCEINLINE
208 | #define __STATIC_FORCEINLINE __STATIC_INLINE
209 | #endif
210 | #ifndef __NO_RETURN
211 | // NO RETURN is automatically detected hence no warning here
212 | #define __NO_RETURN
213 | #endif
214 | #ifndef __USED
215 | #warning No compiler specific solution for __USED. __USED is ignored.
216 | #define __USED
217 | #endif
218 | #ifndef __WEAK
219 | #define __WEAK __weak
220 | #endif
221 | #ifndef __PACKED
222 | #define __PACKED @packed
223 | #endif
224 | #ifndef __PACKED_STRUCT
225 | #define __PACKED_STRUCT @packed struct
226 | #endif
227 | #ifndef __PACKED_UNION
228 | #define __PACKED_UNION @packed union
229 | #endif
230 | #ifndef __UNALIGNED_UINT32 /* deprecated */
231 | @packed struct T_UINT32 { uint32_t v; };
232 | #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v)
233 | #endif
234 | #ifndef __UNALIGNED_UINT16_WRITE
235 | __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; };
236 | #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val))
237 | #endif
238 | #ifndef __UNALIGNED_UINT16_READ
239 | __PACKED_STRUCT T_UINT16_READ { uint16_t v; };
240 | #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v)
241 | #endif
242 | #ifndef __UNALIGNED_UINT32_WRITE
243 | __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; };
244 | #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val))
245 | #endif
246 | #ifndef __UNALIGNED_UINT32_READ
247 | __PACKED_STRUCT T_UINT32_READ { uint32_t v; };
248 | #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v)
249 | #endif
250 | #ifndef __ALIGNED
251 | #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored.
252 | #define __ALIGNED(x)
253 | #endif
254 | #ifndef __RESTRICT
255 | #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored.
256 | #define __RESTRICT
257 | #endif
258 |
259 |
260 | #else
261 | #error Unknown compiler.
262 | #endif
263 |
264 |
265 | #endif /* __CMSIS_COMPILER_H */
266 |
267 |
--------------------------------------------------------------------------------
/Drivers/CMSIS/Include/cmsis_version.h:
--------------------------------------------------------------------------------
1 | /**************************************************************************//**
2 | * @file cmsis_version.h
3 | * @brief CMSIS Core(M) Version definitions
4 | * @version V5.0.2
5 | * @date 19. April 2017
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2009-2017 ARM Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef __CMSIS_VERSION_H
32 | #define __CMSIS_VERSION_H
33 |
34 | /* CMSIS Version definitions */
35 | #define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */
36 | #define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */
37 | #define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \
38 | __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */
39 | #endif
40 |
--------------------------------------------------------------------------------
/Drivers/CMSIS/Include/tz_context.h:
--------------------------------------------------------------------------------
1 | /******************************************************************************
2 | * @file tz_context.h
3 | * @brief Context Management for Armv8-M TrustZone
4 | * @version V1.0.1
5 | * @date 10. January 2018
6 | ******************************************************************************/
7 | /*
8 | * Copyright (c) 2017-2018 Arm Limited. All rights reserved.
9 | *
10 | * SPDX-License-Identifier: Apache-2.0
11 | *
12 | * Licensed under the Apache License, Version 2.0 (the License); you may
13 | * not use this file except in compliance with the License.
14 | * You may obtain a copy of the License at
15 | *
16 | * www.apache.org/licenses/LICENSE-2.0
17 | *
18 | * Unless required by applicable law or agreed to in writing, software
19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT
20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
21 | * See the License for the specific language governing permissions and
22 | * limitations under the License.
23 | */
24 |
25 | #if defined ( __ICCARM__ )
26 | #pragma system_include /* treat file as system include file for MISRA check */
27 | #elif defined (__clang__)
28 | #pragma clang system_header /* treat file as system include file */
29 | #endif
30 |
31 | #ifndef TZ_CONTEXT_H
32 | #define TZ_CONTEXT_H
33 |
34 | #include
35 |
36 | #ifndef TZ_MODULEID_T
37 | #define TZ_MODULEID_T
38 | /// \details Data type that identifies secure software modules called by a process.
39 | typedef uint32_t TZ_ModuleId_t;
40 | #endif
41 |
42 | /// \details TZ Memory ID identifies an allocated memory slot.
43 | typedef uint32_t TZ_MemoryId_t;
44 |
45 | /// Initialize secure context memory system
46 | /// \return execution status (1: success, 0: error)
47 | uint32_t TZ_InitContextSystem_S (void);
48 |
49 | /// Allocate context memory for calling secure software modules in TrustZone
50 | /// \param[in] module identifies software modules called from non-secure mode
51 | /// \return value != 0 id TrustZone memory slot identifier
52 | /// \return value 0 no memory available or internal error
53 | TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module);
54 |
55 | /// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S
56 | /// \param[in] id TrustZone memory slot identifier
57 | /// \return execution status (1: success, 0: error)
58 | uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id);
59 |
60 | /// Load secure context (called on RTOS thread context switch)
61 | /// \param[in] id TrustZone memory slot identifier
62 | /// \return execution status (1: success, 0: error)
63 | uint32_t TZ_LoadContext_S (TZ_MemoryId_t id);
64 |
65 | /// Store secure context (called on RTOS thread context switch)
66 | /// \param[in] id TrustZone memory slot identifier
67 | /// \return execution status (1: success, 0: error)
68 | uint32_t TZ_StoreContext_S (TZ_MemoryId_t id);
69 |
70 | #endif // TZ_CONTEXT_H
71 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_crc.h
4 | * @author MCD Application Team
5 | * @brief Header file of CRC HAL module.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2016 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef STM32F4xx_HAL_CRC_H
22 | #define STM32F4xx_HAL_CRC_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f4xx_hal_def.h"
30 |
31 | /** @addtogroup STM32F4xx_HAL_Driver
32 | * @{
33 | */
34 |
35 | /** @addtogroup CRC
36 | * @{
37 | */
38 |
39 | /* Exported types ------------------------------------------------------------*/
40 | /** @defgroup CRC_Exported_Types CRC Exported Types
41 | * @{
42 | */
43 |
44 | /**
45 | * @brief CRC HAL State Structure definition
46 | */
47 | typedef enum
48 | {
49 | HAL_CRC_STATE_RESET = 0x00U, /*!< CRC not yet initialized or disabled */
50 | HAL_CRC_STATE_READY = 0x01U, /*!< CRC initialized and ready for use */
51 | HAL_CRC_STATE_BUSY = 0x02U, /*!< CRC internal process is ongoing */
52 | HAL_CRC_STATE_TIMEOUT = 0x03U, /*!< CRC timeout state */
53 | HAL_CRC_STATE_ERROR = 0x04U /*!< CRC error state */
54 | } HAL_CRC_StateTypeDef;
55 |
56 |
57 | /**
58 | * @brief CRC Handle Structure definition
59 | */
60 | typedef struct
61 | {
62 | CRC_TypeDef *Instance; /*!< Register base address */
63 |
64 | HAL_LockTypeDef Lock; /*!< CRC Locking object */
65 |
66 | __IO HAL_CRC_StateTypeDef State; /*!< CRC communication state */
67 |
68 | } CRC_HandleTypeDef;
69 | /**
70 | * @}
71 | */
72 |
73 | /* Exported constants --------------------------------------------------------*/
74 | /** @defgroup CRC_Exported_Constants CRC Exported Constants
75 | * @{
76 | */
77 |
78 | /**
79 | * @}
80 | */
81 |
82 | /* Exported macros -----------------------------------------------------------*/
83 | /** @defgroup CRC_Exported_Macros CRC Exported Macros
84 | * @{
85 | */
86 |
87 | /** @brief Reset CRC handle state.
88 | * @param __HANDLE__ CRC handle.
89 | * @retval None
90 | */
91 | #define __HAL_CRC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRC_STATE_RESET)
92 |
93 | /**
94 | * @brief Reset CRC Data Register.
95 | * @param __HANDLE__ CRC handle
96 | * @retval None
97 | */
98 | #define __HAL_CRC_DR_RESET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_RESET)
99 |
100 | /**
101 | * @brief Store data in the Independent Data (ID) register.
102 | * @param __HANDLE__ CRC handle
103 | * @param __VALUE__ Value to be stored in the ID register
104 | * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits
105 | * @retval None
106 | */
107 | #define __HAL_CRC_SET_IDR(__HANDLE__, __VALUE__) (WRITE_REG((__HANDLE__)->Instance->IDR, (__VALUE__)))
108 |
109 | /**
110 | * @brief Return the data stored in the Independent Data (ID) register.
111 | * @param __HANDLE__ CRC handle
112 | * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits
113 | * @retval Value of the ID register
114 | */
115 | #define __HAL_CRC_GET_IDR(__HANDLE__) (((__HANDLE__)->Instance->IDR) & CRC_IDR_IDR)
116 | /**
117 | * @}
118 | */
119 |
120 |
121 | /* Private macros --------------------------------------------------------*/
122 | /** @defgroup CRC_Private_Macros CRC Private Macros
123 | * @{
124 | */
125 |
126 | /**
127 | * @}
128 | */
129 |
130 | /* Exported functions --------------------------------------------------------*/
131 | /** @defgroup CRC_Exported_Functions CRC Exported Functions
132 | * @{
133 | */
134 |
135 | /* Initialization and de-initialization functions ****************************/
136 | /** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions
137 | * @{
138 | */
139 | HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc);
140 | HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc);
141 | void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc);
142 | void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc);
143 | /**
144 | * @}
145 | */
146 |
147 | /* Peripheral Control functions ***********************************************/
148 | /** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions
149 | * @{
150 | */
151 | uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
152 | uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength);
153 | /**
154 | * @}
155 | */
156 |
157 | /* Peripheral State and Error functions ***************************************/
158 | /** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions
159 | * @{
160 | */
161 | HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc);
162 | /**
163 | * @}
164 | */
165 |
166 | /**
167 | * @}
168 | */
169 |
170 | /**
171 | * @}
172 | */
173 |
174 | /**
175 | * @}
176 | */
177 |
178 | #ifdef __cplusplus
179 | }
180 | #endif
181 |
182 | #endif /* STM32F4xx_HAL_CRC_H */
183 |
184 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
185 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_def.h
4 | * @author MCD Application Team
5 | * @brief This file contains HAL common defines, enumeration, macros and
6 | * structures definitions.
7 | ******************************************************************************
8 | * @attention
9 | *
10 | * © Copyright (c) 2017 STMicroelectronics.
11 | * All rights reserved.
12 | *
13 | * This software component is licensed by ST under BSD 3-Clause license,
14 | * the "License"; You may not use this file except in compliance with the
15 | * License. You may obtain a copy of the License at:
16 | * opensource.org/licenses/BSD-3-Clause
17 | *
18 | ******************************************************************************
19 | */
20 |
21 | /* Define to prevent recursive inclusion -------------------------------------*/
22 | #ifndef __STM32F4xx_HAL_DEF
23 | #define __STM32F4xx_HAL_DEF
24 |
25 | #ifdef __cplusplus
26 | extern "C" {
27 | #endif
28 |
29 | /* Includes ------------------------------------------------------------------*/
30 | #include "stm32f4xx.h"
31 | #include "Legacy/stm32_hal_legacy.h"
32 | #include
33 |
34 | /* Exported types ------------------------------------------------------------*/
35 |
36 | /**
37 | * @brief HAL Status structures definition
38 | */
39 | typedef enum
40 | {
41 | HAL_OK = 0x00U,
42 | HAL_ERROR = 0x01U,
43 | HAL_BUSY = 0x02U,
44 | HAL_TIMEOUT = 0x03U
45 | } HAL_StatusTypeDef;
46 |
47 | /**
48 | * @brief HAL Lock structures definition
49 | */
50 | typedef enum
51 | {
52 | HAL_UNLOCKED = 0x00U,
53 | HAL_LOCKED = 0x01U
54 | } HAL_LockTypeDef;
55 |
56 | /* Exported macro ------------------------------------------------------------*/
57 |
58 | #define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */
59 |
60 | #define HAL_MAX_DELAY 0xFFFFFFFFU
61 |
62 | #define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT))
63 | #define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U)
64 |
65 | #define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \
66 | do{ \
67 | (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \
68 | (__DMA_HANDLE__).Parent = (__HANDLE__); \
69 | } while(0U)
70 |
71 | /** @brief Reset the Handle's State field.
72 | * @param __HANDLE__ specifies the Peripheral Handle.
73 | * @note This macro can be used for the following purpose:
74 | * - When the Handle is declared as local variable; before passing it as parameter
75 | * to HAL_PPP_Init() for the first time, it is mandatory to use this macro
76 | * to set to 0 the Handle's "State" field.
77 | * Otherwise, "State" field may have any random value and the first time the function
78 | * HAL_PPP_Init() is called, the low level hardware initialization will be missed
79 | * (i.e. HAL_PPP_MspInit() will not be executed).
80 | * - When there is a need to reconfigure the low level hardware: instead of calling
81 | * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init().
82 | * In this later function, when the Handle's "State" field is set to 0, it will execute the function
83 | * HAL_PPP_MspInit() which will reconfigure the low level hardware.
84 | * @retval None
85 | */
86 | #define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U)
87 |
88 | #if (USE_RTOS == 1U)
89 | /* Reserved for future use */
90 | #error "USE_RTOS should be 0 in the current HAL release"
91 | #else
92 | #define __HAL_LOCK(__HANDLE__) \
93 | do{ \
94 | if((__HANDLE__)->Lock == HAL_LOCKED) \
95 | { \
96 | return HAL_BUSY; \
97 | } \
98 | else \
99 | { \
100 | (__HANDLE__)->Lock = HAL_LOCKED; \
101 | } \
102 | }while (0U)
103 |
104 | #define __HAL_UNLOCK(__HANDLE__) \
105 | do{ \
106 | (__HANDLE__)->Lock = HAL_UNLOCKED; \
107 | }while (0U)
108 | #endif /* USE_RTOS */
109 |
110 | #if defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
111 | #ifndef __weak
112 | #define __weak __attribute__((weak))
113 | #endif /* __weak */
114 | #ifndef __packed
115 | #define __packed __attribute__((__packed__))
116 | #endif /* __packed */
117 | #endif /* __GNUC__ */
118 |
119 |
120 | /* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */
121 | #if defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */
122 | #ifndef __ALIGN_END
123 | #define __ALIGN_END __attribute__ ((aligned (4)))
124 | #endif /* __ALIGN_END */
125 | #ifndef __ALIGN_BEGIN
126 | #define __ALIGN_BEGIN
127 | #endif /* __ALIGN_BEGIN */
128 | #else
129 | #ifndef __ALIGN_END
130 | #define __ALIGN_END
131 | #endif /* __ALIGN_END */
132 | #ifndef __ALIGN_BEGIN
133 | #if defined (__CC_ARM) /* ARM Compiler */
134 | #define __ALIGN_BEGIN __align(4)
135 | #elif defined (__ICCARM__) /* IAR Compiler */
136 | #define __ALIGN_BEGIN
137 | #endif /* __CC_ARM */
138 | #endif /* __ALIGN_BEGIN */
139 | #endif /* __GNUC__ */
140 |
141 |
142 | /**
143 | * @brief __RAM_FUNC definition
144 | */
145 | #if defined ( __CC_ARM )
146 | /* ARM Compiler
147 | ------------
148 | RAM functions are defined using the toolchain options.
149 | Functions that are executed in RAM should reside in a separate source module.
150 | Using the 'Options for File' dialog you can simply change the 'Code / Const'
151 | area of a module to a memory space in physical RAM.
152 | Available memory areas are declared in the 'Target' tab of the 'Options for Target'
153 | dialog.
154 | */
155 | #define __RAM_FUNC
156 |
157 | #elif defined ( __ICCARM__ )
158 | /* ICCARM Compiler
159 | ---------------
160 | RAM functions are defined using a specific toolchain keyword "__ramfunc".
161 | */
162 | #define __RAM_FUNC __ramfunc
163 |
164 | #elif defined ( __GNUC__ )
165 | /* GNU Compiler
166 | ------------
167 | RAM functions are defined using a specific toolchain attribute
168 | "__attribute__((section(".RamFunc")))".
169 | */
170 | #define __RAM_FUNC __attribute__((section(".RamFunc")))
171 |
172 | #endif
173 |
174 | /**
175 | * @brief __NOINLINE definition
176 | */
177 | #if defined ( __CC_ARM ) || defined ( __GNUC__ )
178 | /* ARM & GNUCompiler
179 | ----------------
180 | */
181 | #define __NOINLINE __attribute__ ( (noinline) )
182 |
183 | #elif defined ( __ICCARM__ )
184 | /* ICCARM Compiler
185 | ---------------
186 | */
187 | #define __NOINLINE _Pragma("optimize = no_inline")
188 |
189 | #endif
190 |
191 | #ifdef __cplusplus
192 | }
193 | #endif
194 |
195 | #endif /* ___STM32F4xx_HAL_DEF */
196 |
197 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
198 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_dma_ex.h
4 | * @author MCD Application Team
5 | * @brief Header file of DMA HAL extension module.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2017 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef __STM32F4xx_HAL_DMA_EX_H
22 | #define __STM32F4xx_HAL_DMA_EX_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 |
28 | /* Includes ------------------------------------------------------------------*/
29 | #include "stm32f4xx_hal_def.h"
30 |
31 | /** @addtogroup STM32F4xx_HAL_Driver
32 | * @{
33 | */
34 |
35 | /** @addtogroup DMAEx
36 | * @{
37 | */
38 |
39 | /* Exported types ------------------------------------------------------------*/
40 | /** @defgroup DMAEx_Exported_Types DMAEx Exported Types
41 | * @brief DMAEx Exported types
42 | * @{
43 | */
44 |
45 | /**
46 | * @brief HAL DMA Memory definition
47 | */
48 | typedef enum
49 | {
50 | MEMORY0 = 0x00U, /*!< Memory 0 */
51 | MEMORY1 = 0x01U /*!< Memory 1 */
52 | }HAL_DMA_MemoryTypeDef;
53 |
54 | /**
55 | * @}
56 | */
57 |
58 | /* Exported functions --------------------------------------------------------*/
59 | /** @defgroup DMAEx_Exported_Functions DMAEx Exported Functions
60 | * @brief DMAEx Exported functions
61 | * @{
62 | */
63 |
64 | /** @defgroup DMAEx_Exported_Functions_Group1 Extended features functions
65 | * @brief Extended features functions
66 | * @{
67 | */
68 |
69 | /* IO operation functions *******************************************************/
70 | HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength);
71 | HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength);
72 | HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory);
73 |
74 | /**
75 | * @}
76 | */
77 | /**
78 | * @}
79 | */
80 |
81 | /* Private functions ---------------------------------------------------------*/
82 | /** @defgroup DMAEx_Private_Functions DMAEx Private Functions
83 | * @brief DMAEx Private functions
84 | * @{
85 | */
86 | /**
87 | * @}
88 | */
89 |
90 | /**
91 | * @}
92 | */
93 |
94 | /**
95 | * @}
96 | */
97 |
98 | #ifdef __cplusplus
99 | }
100 | #endif
101 |
102 | #endif /*__STM32F4xx_HAL_DMA_EX_H*/
103 |
104 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
105 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_flash_ramfunc.h
4 | * @author MCD Application Team
5 | * @brief Header file of FLASH RAMFUNC driver.
6 | ******************************************************************************
7 | * @attention
8 | *
9 | * © Copyright (c) 2017 STMicroelectronics.
10 | * All rights reserved.
11 | *
12 | * This software component is licensed by ST under BSD 3-Clause license,
13 | * the "License"; You may not use this file except in compliance with the
14 | * License. You may obtain a copy of the License at:
15 | * opensource.org/licenses/BSD-3-Clause
16 | *
17 | ******************************************************************************
18 | */
19 |
20 | /* Define to prevent recursive inclusion -------------------------------------*/
21 | #ifndef __STM32F4xx_FLASH_RAMFUNC_H
22 | #define __STM32F4xx_FLASH_RAMFUNC_H
23 |
24 | #ifdef __cplusplus
25 | extern "C" {
26 | #endif
27 | #if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\
28 | defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx)
29 |
30 | /* Includes ------------------------------------------------------------------*/
31 | #include "stm32f4xx_hal_def.h"
32 |
33 | /** @addtogroup STM32F4xx_HAL_Driver
34 | * @{
35 | */
36 |
37 | /** @addtogroup FLASH_RAMFUNC
38 | * @{
39 | */
40 |
41 | /* Exported types ------------------------------------------------------------*/
42 | /* Exported macro ------------------------------------------------------------*/
43 | /* Exported functions --------------------------------------------------------*/
44 | /** @addtogroup FLASH_RAMFUNC_Exported_Functions
45 | * @{
46 | */
47 |
48 | /** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1
49 | * @{
50 | */
51 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void);
52 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void);
53 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void);
54 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void);
55 | /**
56 | * @}
57 | */
58 |
59 | /**
60 | * @}
61 | */
62 |
63 | /**
64 | * @}
65 | */
66 |
67 | /**
68 | * @}
69 | */
70 |
71 | #endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */
72 | #ifdef __cplusplus
73 | }
74 | #endif
75 |
76 |
77 | #endif /* __STM32F4xx_FLASH_RAMFUNC_H */
78 |
79 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
80 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_crc.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_crc.c
4 | * @author MCD Application Team
5 | * @brief CRC HAL module driver.
6 | * This file provides firmware functions to manage the following
7 | * functionalities of the Cyclic Redundancy Check (CRC) peripheral:
8 | * + Initialization and de-initialization functions
9 | * + Peripheral Control functions
10 | * + Peripheral State functions
11 | *
12 | @verbatim
13 | ===============================================================================
14 | ##### How to use this driver #####
15 | ===============================================================================
16 | [..]
17 | (+) Enable CRC AHB clock using __HAL_RCC_CRC_CLK_ENABLE();
18 | (+) Initialize CRC calculator
19 | (++) specify generating polynomial (peripheral default or non-default one)
20 | (++) specify initialization value (peripheral default or non-default one)
21 | (++) specify input data format
22 | (++) specify input or output data inversion mode if any
23 | (+) Use HAL_CRC_Accumulate() function to compute the CRC value of the
24 | input data buffer starting with the previously computed CRC as
25 | initialization value
26 | (+) Use HAL_CRC_Calculate() function to compute the CRC value of the
27 | input data buffer starting with the defined initialization value
28 | (default or non-default) to initiate CRC calculation
29 |
30 | @endverbatim
31 | ******************************************************************************
32 | * @attention
33 | *
34 | * © Copyright (c) 2016 STMicroelectronics.
35 | * All rights reserved.
36 | *
37 | * This software component is licensed by ST under BSD 3-Clause license,
38 | * the "License"; You may not use this file except in compliance with the
39 | * License. You may obtain a copy of the License at:
40 | * opensource.org/licenses/BSD-3-Clause
41 | *
42 | ******************************************************************************
43 | */
44 |
45 | /* Includes ------------------------------------------------------------------*/
46 | #include "stm32f4xx_hal.h"
47 |
48 | /** @addtogroup STM32F4xx_HAL_Driver
49 | * @{
50 | */
51 |
52 | /** @defgroup CRC CRC
53 | * @brief CRC HAL module driver.
54 | * @{
55 | */
56 |
57 | #ifdef HAL_CRC_MODULE_ENABLED
58 |
59 | /* Private typedef -----------------------------------------------------------*/
60 | /* Private define ------------------------------------------------------------*/
61 | /* Private macro -------------------------------------------------------------*/
62 | /* Private variables ---------------------------------------------------------*/
63 | /* Private function prototypes -----------------------------------------------*/
64 |
65 | /* Exported functions --------------------------------------------------------*/
66 |
67 | /** @defgroup CRC_Exported_Functions CRC Exported Functions
68 | * @{
69 | */
70 |
71 | /** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions
72 | * @brief Initialization and Configuration functions.
73 | *
74 | @verbatim
75 | ===============================================================================
76 | ##### Initialization and de-initialization functions #####
77 | ===============================================================================
78 | [..] This section provides functions allowing to:
79 | (+) Initialize the CRC according to the specified parameters
80 | in the CRC_InitTypeDef and create the associated handle
81 | (+) DeInitialize the CRC peripheral
82 | (+) Initialize the CRC MSP (MCU Specific Package)
83 | (+) DeInitialize the CRC MSP
84 |
85 | @endverbatim
86 | * @{
87 | */
88 |
89 | /**
90 | * @brief Initialize the CRC according to the specified
91 | * parameters in the CRC_InitTypeDef and create the associated handle.
92 | * @param hcrc CRC handle
93 | * @retval HAL status
94 | */
95 | HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc)
96 | {
97 | /* Check the CRC handle allocation */
98 | if (hcrc == NULL)
99 | {
100 | return HAL_ERROR;
101 | }
102 |
103 | /* Check the parameters */
104 | assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance));
105 |
106 | if (hcrc->State == HAL_CRC_STATE_RESET)
107 | {
108 | /* Allocate lock resource and initialize it */
109 | hcrc->Lock = HAL_UNLOCKED;
110 | /* Init the low level hardware */
111 | HAL_CRC_MspInit(hcrc);
112 | }
113 |
114 | /* Change CRC peripheral state */
115 | hcrc->State = HAL_CRC_STATE_READY;
116 |
117 | /* Return function status */
118 | return HAL_OK;
119 | }
120 |
121 | /**
122 | * @brief DeInitialize the CRC peripheral.
123 | * @param hcrc CRC handle
124 | * @retval HAL status
125 | */
126 | HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc)
127 | {
128 | /* Check the CRC handle allocation */
129 | if (hcrc == NULL)
130 | {
131 | return HAL_ERROR;
132 | }
133 |
134 | /* Check the parameters */
135 | assert_param(IS_CRC_ALL_INSTANCE(hcrc->Instance));
136 |
137 | /* Check the CRC peripheral state */
138 | if (hcrc->State == HAL_CRC_STATE_BUSY)
139 | {
140 | return HAL_BUSY;
141 | }
142 |
143 | /* Change CRC peripheral state */
144 | hcrc->State = HAL_CRC_STATE_BUSY;
145 |
146 | /* Reset CRC calculation unit */
147 | __HAL_CRC_DR_RESET(hcrc);
148 |
149 | /* Reset IDR register content */
150 | CLEAR_BIT(hcrc->Instance->IDR, CRC_IDR_IDR);
151 |
152 | /* DeInit the low level hardware */
153 | HAL_CRC_MspDeInit(hcrc);
154 |
155 | /* Change CRC peripheral state */
156 | hcrc->State = HAL_CRC_STATE_RESET;
157 |
158 | /* Process unlocked */
159 | __HAL_UNLOCK(hcrc);
160 |
161 | /* Return function status */
162 | return HAL_OK;
163 | }
164 |
165 | /**
166 | * @brief Initializes the CRC MSP.
167 | * @param hcrc CRC handle
168 | * @retval None
169 | */
170 | __weak void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc)
171 | {
172 | /* Prevent unused argument(s) compilation warning */
173 | UNUSED(hcrc);
174 |
175 | /* NOTE : This function should not be modified, when the callback is needed,
176 | the HAL_CRC_MspInit can be implemented in the user file
177 | */
178 | }
179 |
180 | /**
181 | * @brief DeInitialize the CRC MSP.
182 | * @param hcrc CRC handle
183 | * @retval None
184 | */
185 | __weak void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc)
186 | {
187 | /* Prevent unused argument(s) compilation warning */
188 | UNUSED(hcrc);
189 |
190 | /* NOTE : This function should not be modified, when the callback is needed,
191 | the HAL_CRC_MspDeInit can be implemented in the user file
192 | */
193 | }
194 |
195 | /**
196 | * @}
197 | */
198 |
199 | /** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions
200 | * @brief management functions.
201 | *
202 | @verbatim
203 | ===============================================================================
204 | ##### Peripheral Control functions #####
205 | ===============================================================================
206 | [..] This section provides functions allowing to:
207 | (+) compute the 32-bit CRC value of a 32-bit data buffer
208 | using combination of the previous CRC value and the new one.
209 |
210 | [..] or
211 |
212 | (+) compute the 32-bit CRC value of a 32-bit data buffer
213 | independently of the previous CRC value.
214 |
215 | @endverbatim
216 | * @{
217 | */
218 |
219 | /**
220 | * @brief Compute the 32-bit CRC value of a 32-bit data buffer
221 | * starting with the previously computed CRC as initialization value.
222 | * @param hcrc CRC handle
223 | * @param pBuffer pointer to the input data buffer.
224 | * @param BufferLength input data buffer length (number of uint32_t words).
225 | * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
226 | */
227 | uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
228 | {
229 | uint32_t index; /* CRC input data buffer index */
230 | uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */
231 |
232 | /* Change CRC peripheral state */
233 | hcrc->State = HAL_CRC_STATE_BUSY;
234 |
235 | /* Enter Data to the CRC calculator */
236 | for (index = 0U; index < BufferLength; index++)
237 | {
238 | hcrc->Instance->DR = pBuffer[index];
239 | }
240 | temp = hcrc->Instance->DR;
241 |
242 | /* Change CRC peripheral state */
243 | hcrc->State = HAL_CRC_STATE_READY;
244 |
245 | /* Return the CRC computed value */
246 | return temp;
247 | }
248 |
249 | /**
250 | * @brief Compute the 32-bit CRC value of a 32-bit data buffer
251 | * starting with hcrc->Instance->INIT as initialization value.
252 | * @param hcrc CRC handle
253 | * @param pBuffer pointer to the input data buffer.
254 | * @param BufferLength input data buffer length (number of uint32_t words).
255 | * @retval uint32_t CRC (returned value LSBs for CRC shorter than 32 bits)
256 | */
257 | uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength)
258 | {
259 | uint32_t index; /* CRC input data buffer index */
260 | uint32_t temp = 0U; /* CRC output (read from hcrc->Instance->DR register) */
261 |
262 | /* Change CRC peripheral state */
263 | hcrc->State = HAL_CRC_STATE_BUSY;
264 |
265 | /* Reset CRC Calculation Unit (hcrc->Instance->INIT is
266 | * written in hcrc->Instance->DR) */
267 | __HAL_CRC_DR_RESET(hcrc);
268 |
269 | /* Enter 32-bit input data to the CRC calculator */
270 | for (index = 0U; index < BufferLength; index++)
271 | {
272 | hcrc->Instance->DR = pBuffer[index];
273 | }
274 | temp = hcrc->Instance->DR;
275 |
276 | /* Change CRC peripheral state */
277 | hcrc->State = HAL_CRC_STATE_READY;
278 |
279 | /* Return the CRC computed value */
280 | return temp;
281 | }
282 |
283 | /**
284 | * @}
285 | */
286 |
287 | /** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions
288 | * @brief Peripheral State functions.
289 | *
290 | @verbatim
291 | ===============================================================================
292 | ##### Peripheral State functions #####
293 | ===============================================================================
294 | [..]
295 | This subsection permits to get in run-time the status of the peripheral.
296 |
297 | @endverbatim
298 | * @{
299 | */
300 |
301 | /**
302 | * @brief Return the CRC handle state.
303 | * @param hcrc CRC handle
304 | * @retval HAL state
305 | */
306 | HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc)
307 | {
308 | /* Return CRC handle state */
309 | return hcrc->State;
310 | }
311 |
312 | /**
313 | * @}
314 | */
315 |
316 | /**
317 | * @}
318 | */
319 |
320 |
321 | #endif /* HAL_CRC_MODULE_ENABLED */
322 | /**
323 | * @}
324 | */
325 |
326 | /**
327 | * @}
328 | */
329 |
330 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
331 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma_ex.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_dma_ex.c
4 | * @author MCD Application Team
5 | * @brief DMA Extension HAL module driver
6 | * This file provides firmware functions to manage the following
7 | * functionalities of the DMA Extension peripheral:
8 | * + Extended features functions
9 | *
10 | @verbatim
11 | ==============================================================================
12 | ##### How to use this driver #####
13 | ==============================================================================
14 | [..]
15 | The DMA Extension HAL driver can be used as follows:
16 | (#) Start a multi buffer transfer using the HAL_DMA_MultiBufferStart() function
17 | for polling mode or HAL_DMA_MultiBufferStart_IT() for interrupt mode.
18 |
19 | -@- In Memory-to-Memory transfer mode, Multi (Double) Buffer mode is not allowed.
20 | -@- When Multi (Double) Buffer mode is enabled the, transfer is circular by default.
21 | -@- In Multi (Double) buffer mode, it is possible to update the base address for
22 | the AHB memory port on the fly (DMA_SxM0AR or DMA_SxM1AR) when the stream is enabled.
23 |
24 | @endverbatim
25 | ******************************************************************************
26 | * @attention
27 | *
28 | * © Copyright (c) 2017 STMicroelectronics.
29 | * All rights reserved.
30 | *
31 | * This software component is licensed by ST under BSD 3-Clause license,
32 | * the "License"; You may not use this file except in compliance with the
33 | * License. You may obtain a copy of the License at:
34 | * opensource.org/licenses/BSD-3-Clause
35 | *
36 | ******************************************************************************
37 | */
38 |
39 | /* Includes ------------------------------------------------------------------*/
40 | #include "stm32f4xx_hal.h"
41 |
42 | /** @addtogroup STM32F4xx_HAL_Driver
43 | * @{
44 | */
45 |
46 | /** @defgroup DMAEx DMAEx
47 | * @brief DMA Extended HAL module driver
48 | * @{
49 | */
50 |
51 | #ifdef HAL_DMA_MODULE_ENABLED
52 |
53 | /* Private types -------------------------------------------------------------*/
54 | /* Private variables ---------------------------------------------------------*/
55 | /* Private Constants ---------------------------------------------------------*/
56 | /* Private macros ------------------------------------------------------------*/
57 | /* Private functions ---------------------------------------------------------*/
58 | /** @addtogroup DMAEx_Private_Functions
59 | * @{
60 | */
61 | static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength);
62 | /**
63 | * @}
64 | */
65 |
66 | /* Exported functions ---------------------------------------------------------*/
67 |
68 | /** @addtogroup DMAEx_Exported_Functions
69 | * @{
70 | */
71 |
72 |
73 | /** @addtogroup DMAEx_Exported_Functions_Group1
74 | *
75 | @verbatim
76 | ===============================================================================
77 | ##### Extended features functions #####
78 | ===============================================================================
79 | [..] This section provides functions allowing to:
80 | (+) Configure the source, destination address and data length and
81 | Start MultiBuffer DMA transfer
82 | (+) Configure the source, destination address and data length and
83 | Start MultiBuffer DMA transfer with interrupt
84 | (+) Change on the fly the memory0 or memory1 address.
85 |
86 | @endverbatim
87 | * @{
88 | */
89 |
90 |
91 | /**
92 | * @brief Starts the multi_buffer DMA Transfer.
93 | * @param hdma pointer to a DMA_HandleTypeDef structure that contains
94 | * the configuration information for the specified DMA Stream.
95 | * @param SrcAddress The source memory Buffer address
96 | * @param DstAddress The destination memory Buffer address
97 | * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer
98 | * @param DataLength The length of data to be transferred from source to destination
99 | * @retval HAL status
100 | */
101 | HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength)
102 | {
103 | HAL_StatusTypeDef status = HAL_OK;
104 |
105 | /* Check the parameters */
106 | assert_param(IS_DMA_BUFFER_SIZE(DataLength));
107 |
108 | /* Memory-to-memory transfer not supported in double buffering mode */
109 | if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY)
110 | {
111 | hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
112 | status = HAL_ERROR;
113 | }
114 | else
115 | {
116 | /* Process Locked */
117 | __HAL_LOCK(hdma);
118 |
119 | if(HAL_DMA_STATE_READY == hdma->State)
120 | {
121 | /* Change DMA peripheral state */
122 | hdma->State = HAL_DMA_STATE_BUSY;
123 |
124 | /* Enable the double buffer mode */
125 | hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM;
126 |
127 | /* Configure DMA Stream destination address */
128 | hdma->Instance->M1AR = SecondMemAddress;
129 |
130 | /* Configure the source, destination address and the data length */
131 | DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength);
132 |
133 | /* Enable the peripheral */
134 | __HAL_DMA_ENABLE(hdma);
135 | }
136 | else
137 | {
138 | /* Return error status */
139 | status = HAL_BUSY;
140 | }
141 | }
142 | return status;
143 | }
144 |
145 | /**
146 | * @brief Starts the multi_buffer DMA Transfer with interrupt enabled.
147 | * @param hdma pointer to a DMA_HandleTypeDef structure that contains
148 | * the configuration information for the specified DMA Stream.
149 | * @param SrcAddress The source memory Buffer address
150 | * @param DstAddress The destination memory Buffer address
151 | * @param SecondMemAddress The second memory Buffer address in case of multi buffer Transfer
152 | * @param DataLength The length of data to be transferred from source to destination
153 | * @retval HAL status
154 | */
155 | HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength)
156 | {
157 | HAL_StatusTypeDef status = HAL_OK;
158 |
159 | /* Check the parameters */
160 | assert_param(IS_DMA_BUFFER_SIZE(DataLength));
161 |
162 | /* Memory-to-memory transfer not supported in double buffering mode */
163 | if (hdma->Init.Direction == DMA_MEMORY_TO_MEMORY)
164 | {
165 | hdma->ErrorCode = HAL_DMA_ERROR_NOT_SUPPORTED;
166 | return HAL_ERROR;
167 | }
168 |
169 | /* Check callback functions */
170 | if ((NULL == hdma->XferCpltCallback) || (NULL == hdma->XferM1CpltCallback) || (NULL == hdma->XferErrorCallback))
171 | {
172 | hdma->ErrorCode = HAL_DMA_ERROR_PARAM;
173 | return HAL_ERROR;
174 | }
175 |
176 | /* Process locked */
177 | __HAL_LOCK(hdma);
178 |
179 | if(HAL_DMA_STATE_READY == hdma->State)
180 | {
181 | /* Change DMA peripheral state */
182 | hdma->State = HAL_DMA_STATE_BUSY;
183 |
184 | /* Initialize the error code */
185 | hdma->ErrorCode = HAL_DMA_ERROR_NONE;
186 |
187 | /* Enable the Double buffer mode */
188 | hdma->Instance->CR |= (uint32_t)DMA_SxCR_DBM;
189 |
190 | /* Configure DMA Stream destination address */
191 | hdma->Instance->M1AR = SecondMemAddress;
192 |
193 | /* Configure the source, destination address and the data length */
194 | DMA_MultiBufferSetConfig(hdma, SrcAddress, DstAddress, DataLength);
195 |
196 | /* Clear all flags */
197 | __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TC_FLAG_INDEX(hdma));
198 | __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_HT_FLAG_INDEX(hdma));
199 | __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_TE_FLAG_INDEX(hdma));
200 | __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_DME_FLAG_INDEX(hdma));
201 | __HAL_DMA_CLEAR_FLAG (hdma, __HAL_DMA_GET_FE_FLAG_INDEX(hdma));
202 |
203 | /* Enable Common interrupts*/
204 | hdma->Instance->CR |= DMA_IT_TC | DMA_IT_TE | DMA_IT_DME;
205 | hdma->Instance->FCR |= DMA_IT_FE;
206 |
207 | if((hdma->XferHalfCpltCallback != NULL) || (hdma->XferM1HalfCpltCallback != NULL))
208 | {
209 | hdma->Instance->CR |= DMA_IT_HT;
210 | }
211 |
212 | /* Enable the peripheral */
213 | __HAL_DMA_ENABLE(hdma);
214 | }
215 | else
216 | {
217 | /* Process unlocked */
218 | __HAL_UNLOCK(hdma);
219 |
220 | /* Return error status */
221 | status = HAL_BUSY;
222 | }
223 | return status;
224 | }
225 |
226 | /**
227 | * @brief Change the memory0 or memory1 address on the fly.
228 | * @param hdma pointer to a DMA_HandleTypeDef structure that contains
229 | * the configuration information for the specified DMA Stream.
230 | * @param Address The new address
231 | * @param memory the memory to be changed, This parameter can be one of
232 | * the following values:
233 | * MEMORY0 /
234 | * MEMORY1
235 | * @note The MEMORY0 address can be changed only when the current transfer use
236 | * MEMORY1 and the MEMORY1 address can be changed only when the current
237 | * transfer use MEMORY0.
238 | * @retval HAL status
239 | */
240 | HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory)
241 | {
242 | if(memory == MEMORY0)
243 | {
244 | /* change the memory0 address */
245 | hdma->Instance->M0AR = Address;
246 | }
247 | else
248 | {
249 | /* change the memory1 address */
250 | hdma->Instance->M1AR = Address;
251 | }
252 |
253 | return HAL_OK;
254 | }
255 |
256 | /**
257 | * @}
258 | */
259 |
260 | /**
261 | * @}
262 | */
263 |
264 | /** @addtogroup DMAEx_Private_Functions
265 | * @{
266 | */
267 |
268 | /**
269 | * @brief Set the DMA Transfer parameter.
270 | * @param hdma pointer to a DMA_HandleTypeDef structure that contains
271 | * the configuration information for the specified DMA Stream.
272 | * @param SrcAddress The source memory Buffer address
273 | * @param DstAddress The destination memory Buffer address
274 | * @param DataLength The length of data to be transferred from source to destination
275 | * @retval HAL status
276 | */
277 | static void DMA_MultiBufferSetConfig(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength)
278 | {
279 | /* Configure DMA Stream data length */
280 | hdma->Instance->NDTR = DataLength;
281 |
282 | /* Peripheral to Memory */
283 | if((hdma->Init.Direction) == DMA_MEMORY_TO_PERIPH)
284 | {
285 | /* Configure DMA Stream destination address */
286 | hdma->Instance->PAR = DstAddress;
287 |
288 | /* Configure DMA Stream source address */
289 | hdma->Instance->M0AR = SrcAddress;
290 | }
291 | /* Memory to Peripheral */
292 | else
293 | {
294 | /* Configure DMA Stream source address */
295 | hdma->Instance->PAR = SrcAddress;
296 |
297 | /* Configure DMA Stream destination address */
298 | hdma->Instance->M0AR = DstAddress;
299 | }
300 | }
301 |
302 | /**
303 | * @}
304 | */
305 |
306 | #endif /* HAL_DMA_MODULE_ENABLED */
307 | /**
308 | * @}
309 | */
310 |
311 | /**
312 | * @}
313 | */
314 |
315 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
316 |
--------------------------------------------------------------------------------
/Drivers/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ramfunc.c:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_hal_flash_ramfunc.c
4 | * @author MCD Application Team
5 | * @brief FLASH RAMFUNC module driver.
6 | * This file provides a FLASH firmware functions which should be
7 | * executed from internal SRAM
8 | * + Stop/Start the flash interface while System Run
9 | * + Enable/Disable the flash sleep while System Run
10 | @verbatim
11 | ==============================================================================
12 | ##### APIs executed from Internal RAM #####
13 | ==============================================================================
14 | [..]
15 | *** ARM Compiler ***
16 | --------------------
17 | [..] RAM functions are defined using the toolchain options.
18 | Functions that are be executed in RAM should reside in a separate
19 | source module. Using the 'Options for File' dialog you can simply change
20 | the 'Code / Const' area of a module to a memory space in physical RAM.
21 | Available memory areas are declared in the 'Target' tab of the
22 | Options for Target' dialog.
23 |
24 | *** ICCARM Compiler ***
25 | -----------------------
26 | [..] RAM functions are defined using a specific toolchain keyword "__ramfunc".
27 |
28 | *** GNU Compiler ***
29 | --------------------
30 | [..] RAM functions are defined using a specific toolchain attribute
31 | "__attribute__((section(".RamFunc")))".
32 |
33 | @endverbatim
34 | ******************************************************************************
35 | * @attention
36 | *
37 | * © Copyright (c) 2017 STMicroelectronics.
38 | * All rights reserved.
39 | *
40 | * This software component is licensed by ST under BSD 3-Clause license,
41 | * the "License"; You may not use this file except in compliance with the
42 | * License. You may obtain a copy of the License at:
43 | * opensource.org/licenses/BSD-3-Clause
44 | *
45 | ******************************************************************************
46 | */
47 |
48 | /* Includes ------------------------------------------------------------------*/
49 | #include "stm32f4xx_hal.h"
50 |
51 | /** @addtogroup STM32F4xx_HAL_Driver
52 | * @{
53 | */
54 |
55 | /** @defgroup FLASH_RAMFUNC FLASH RAMFUNC
56 | * @brief FLASH functions executed from RAM
57 | * @{
58 | */
59 | #ifdef HAL_FLASH_MODULE_ENABLED
60 | #if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \
61 | defined(STM32F412Rx) || defined(STM32F412Cx)
62 |
63 | /* Private typedef -----------------------------------------------------------*/
64 | /* Private define ------------------------------------------------------------*/
65 | /* Private macro -------------------------------------------------------------*/
66 | /* Private variables ---------------------------------------------------------*/
67 | /* Private function prototypes -----------------------------------------------*/
68 | /* Exported functions --------------------------------------------------------*/
69 | /** @defgroup FLASH_RAMFUNC_Exported_Functions FLASH RAMFUNC Exported Functions
70 | * @{
71 | */
72 |
73 | /** @defgroup FLASH_RAMFUNC_Exported_Functions_Group1 Peripheral features functions executed from internal RAM
74 | * @brief Peripheral Extended features functions
75 | *
76 | @verbatim
77 |
78 | ===============================================================================
79 | ##### ramfunc functions #####
80 | ===============================================================================
81 | [..]
82 | This subsection provides a set of functions that should be executed from RAM
83 | transfers.
84 |
85 | @endverbatim
86 | * @{
87 | */
88 |
89 | /**
90 | * @brief Stop the flash interface while System Run
91 | * @note This mode is only available for STM32F41xxx/STM32F446xx devices.
92 | * @note This mode couldn't be set while executing with the flash itself.
93 | * It should be done with specific routine executed from RAM.
94 | * @retval HAL status
95 | */
96 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void)
97 | {
98 | /* Enable Power ctrl clock */
99 | __HAL_RCC_PWR_CLK_ENABLE();
100 | /* Stop the flash interface while System Run */
101 | SET_BIT(PWR->CR, PWR_CR_FISSR);
102 |
103 | return HAL_OK;
104 | }
105 |
106 | /**
107 | * @brief Start the flash interface while System Run
108 | * @note This mode is only available for STM32F411xx/STM32F446xx devices.
109 | * @note This mode couldn't be set while executing with the flash itself.
110 | * It should be done with specific routine executed from RAM.
111 | * @retval HAL status
112 | */
113 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void)
114 | {
115 | /* Enable Power ctrl clock */
116 | __HAL_RCC_PWR_CLK_ENABLE();
117 | /* Start the flash interface while System Run */
118 | CLEAR_BIT(PWR->CR, PWR_CR_FISSR);
119 |
120 | return HAL_OK;
121 | }
122 |
123 | /**
124 | * @brief Enable the flash sleep while System Run
125 | * @note This mode is only available for STM32F41xxx/STM32F446xx devices.
126 | * @note This mode could n't be set while executing with the flash itself.
127 | * It should be done with specific routine executed from RAM.
128 | * @retval HAL status
129 | */
130 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void)
131 | {
132 | /* Enable Power ctrl clock */
133 | __HAL_RCC_PWR_CLK_ENABLE();
134 | /* Enable the flash sleep while System Run */
135 | SET_BIT(PWR->CR, PWR_CR_FMSSR);
136 |
137 | return HAL_OK;
138 | }
139 |
140 | /**
141 | * @brief Disable the flash sleep while System Run
142 | * @note This mode is only available for STM32F41xxx/STM32F446xx devices.
143 | * @note This mode couldn't be set while executing with the flash itself.
144 | * It should be done with specific routine executed from RAM.
145 | * @retval HAL status
146 | */
147 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void)
148 | {
149 | /* Enable Power ctrl clock */
150 | __HAL_RCC_PWR_CLK_ENABLE();
151 | /* Disable the flash sleep while System Run */
152 | CLEAR_BIT(PWR->CR, PWR_CR_FMSSR);
153 |
154 | return HAL_OK;
155 | }
156 |
157 | /**
158 | * @}
159 | */
160 |
161 | /**
162 | * @}
163 | */
164 |
165 | #endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */
166 | #endif /* HAL_FLASH_MODULE_ENABLED */
167 | /**
168 | * @}
169 | */
170 |
171 | /**
172 | * @}
173 | */
174 |
175 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
176 |
--------------------------------------------------------------------------------
/Encoder/AS5047.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | uint8_t dataTx[2] = { 0xFF, 0xFF };
4 | uint8_t *dataRx;
5 |
6 | int32_t incrementalCounter = 0;
7 | uint8_t EncoderAPrev = 0;
8 |
9 | void AS5047::UpdateEncoderPoll()
10 | {
11 | SPITransmitPool(dataTx, 2);
12 | dataRx = SPIReceive();
13 |
14 | SPITransmitPool(dataTx, 2);
15 | dataRx = SPIReceive();
16 |
17 | Update();
18 | }
19 |
20 | void AS5047::UpdateEncoder()
21 | {
22 | SPITransmit(dataTx, 2);
23 | dataRx = SPIReceive();
24 |
25 | Update();
26 | }
27 |
28 | void AS5047::Update()
29 | {
30 | encoderRawData = (((dataRx[0] & 0xFF) << 8) | (dataRx[1] & 0xFF)) & ~0xC000;
31 |
32 | jointPosition = (float) encoderRawData * ((float) M_PI * 2.0f) / 16383.0f;
33 | jointPosition -= encoderOffset;
34 |
35 | if (jointPosition > (float) M_PI * 2.0f)
36 | {
37 | jointPosition -= (float) M_PI * 2.0f;
38 | }
39 | else if (jointPosition < 0.0f)
40 | {
41 | jointPosition += (float) M_PI * 2.0f;
42 | }
43 |
44 | float rotorPositionRaw = jointPosition * (float) polePair;
45 |
46 | while (rotorPositionRaw > (float) M_PI * 2.0f)
47 | {
48 | rotorPositionRaw -= (float) M_PI * 2.0f;
49 | }
50 |
51 | rotorPosition = rotorPositionRaw;
52 |
53 | uint8_t EncoderA, EncoderB, ARising, AFalling;
54 |
55 | if (encoderRawData >= 0 && encoderRawData < (16383 / 8 * 2))
56 | {
57 | EncoderA = 1;
58 | }
59 | else
60 | {
61 | EncoderA = 0;
62 | }
63 |
64 | if (encoderRawData >= (16383 / 8 * 1) && encoderRawData < (16383 / 8 * 3))
65 | {
66 | EncoderB = 1;
67 | }
68 | else
69 | {
70 | EncoderB = 0;
71 | }
72 |
73 | if (EncoderAPrev == 0 && EncoderA == 1)
74 | {
75 | ARising = 1;
76 | }
77 | else
78 | {
79 | ARising = 0;
80 | }
81 |
82 | if (EncoderAPrev == 1 && EncoderA == 0)
83 | {
84 | AFalling = 1;
85 | }
86 | else
87 | {
88 | AFalling = 0;
89 | }
90 |
91 | if (ARising == 1 && EncoderB == 0)
92 | {
93 | incrementalCounter++;
94 | }
95 | else if (AFalling == 1 && EncoderB == 0)
96 | {
97 | incrementalCounter--;
98 | }
99 |
100 | EncoderAPrev = EncoderA;
101 |
102 | extendedJointPosition = (float) incrementalCounter * (float) (M_PI * 2.0) + (float) encoderRawData * ((float) (M_PI * 2.0) / 16383.0f);
103 | extendedJointPosition -= encoderOffset;
104 | extendedJointPosition = filter_pos.Update(extendedJointPosition);
105 |
106 |
107 | jointVelocity = (extendedJointPosition - extendedJointPositionPrev[positionBufferIdx]) / (DELTA_T * 10.0f);
108 | jointVelocity = filter_vel.Update(jointVelocity);
109 | extendedJointPositionPrev[positionBufferIdx++] = extendedJointPosition;
110 |
111 | if (positionBufferIdx >= 10)
112 | {
113 | positionBufferIdx = 0;
114 | }
115 | }
116 |
117 | uint16_t AS5047::GetRawData()
118 | {
119 | return encoderRawData;
120 | }
121 |
122 | float AS5047::GetJointPosition()
123 | {
124 | return jointPosition;
125 | }
126 |
127 | float AS5047::GetRotorPosition()
128 | {
129 | return rotorPosition;
130 | }
131 |
132 | float AS5047::GetExtendedJointPosition()
133 | {
134 | return extendedJointPosition;
135 | }
136 |
137 | float AS5047::GetJointVelocity()
138 | {
139 | return jointVelocity;
140 | }
141 |
--------------------------------------------------------------------------------
/Encoder/AS5047.hpp:
--------------------------------------------------------------------------------
1 | #ifndef AS5047_HPP_
2 | #define AS5047_HPP_
3 |
4 | #define _USE_MATH_DEFINES
5 |
6 | #include
7 | #include
8 | #include
9 | #include
10 |
11 | class AS5047
12 | {
13 | public:
14 | LowPass filter_vel = LowPass();
15 | LowPass filter_pos = LowPass();
16 |
17 | void UpdateEncoder();
18 | void UpdateEncoderPoll();
19 | uint16_t GetRawData();
20 | float GetJointPosition();
21 | float GetRotorPosition();
22 | float GetExtendedJointPosition();
23 | float GetJointVelocity();
24 |
25 | uint32_t polePair;
26 | float encoderOffset = 0.0f;
27 |
28 | private:
29 | void Update();
30 |
31 | uint16_t encoderRawData = 0;
32 |
33 | float jointVelocity = 0.0f;
34 | float jointPosition = 0.0f;
35 | float rotorPosition = 0.0f;
36 | float extendedJointPosition = 0.0f;
37 | float extendedJointPositionPrev[10] = { 0, };
38 | uint8_t positionBufferIdx = 0;
39 | };
40 |
41 | #endif
42 |
--------------------------------------------------------------------------------
/ErrorControl/errorControl.hpp:
--------------------------------------------------------------------------------
1 | #ifndef ERRORCONTROL_HPP_
2 | #define ERRORCONTROL_HPP_
3 |
4 | #define BATTERY_VOLTAGE_ERROR_MASK 0b00001
5 | #define VOLTAGE_ERROR_MASK 0b00010
6 | #define ELECTRICAL_SHOCK_ERROR_MASK 0b00100
7 | #define BOARD_TEMPERATURE_ERROR_MASK 0b01000
8 | #define MOTOR_TEMPERATURE_ERROR_MASK 0b10000
9 |
10 | #endif
11 |
--------------------------------------------------------------------------------
/FastMath/fast_math.cpp:
--------------------------------------------------------------------------------
1 | #include "fast_math.hpp"
2 | #include
3 |
4 | float sineTable[FAST_MATH_TABLE_SIZE];
5 |
6 | void FastMathInit()
7 | {
8 | double x = 0.0f;
9 |
10 | for (uint32_t i = 0; i < FAST_MATH_TABLE_SIZE; i++)
11 | {
12 | sineTable[i] = (float) sin(x);
13 |
14 | x += (M_PI * 2.0) / (double) FAST_MATH_TABLE_SIZE;
15 | }
16 | }
17 |
18 | float FastSin(float x)
19 | {
20 | x -= (float) (M_PI * 2.0) * (float) ((int32_t) (x / (float) (M_PI * 2.0)));
21 |
22 | uint32_t idx = (uint32_t) (x * ((double) FAST_MATH_TABLE_SIZE / (M_PI * 2.0)));
23 |
24 | return sineTable[idx];
25 | }
26 |
27 | float FastCos(float x)
28 | {
29 | x += (float) M_PI / 2.0f;
30 | x -= (float) (M_PI * 2.0) * (float) ((int32_t) (x / (float) (M_PI * 2.0)));
31 |
32 | uint32_t idx = (uint32_t) (x * ((double) FAST_MATH_TABLE_SIZE / (M_PI * 2.0)));
33 |
34 | return sineTable[idx];
35 | }
36 |
--------------------------------------------------------------------------------
/FastMath/fast_math.hpp:
--------------------------------------------------------------------------------
1 | #ifndef FAST_MATH_HPP_
2 | #define FAST_MATH_HPP_
3 |
4 | #include
5 | #define _USE_MATH_DEFINES
6 | #include
7 |
8 | void FastMathInit();
9 | float FastSin(float x);
10 | float FastCos(float x);
11 |
12 | #endif
13 |
--------------------------------------------------------------------------------
/Images/PCB_Image.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/jwkim04/J-Drive/d0f84098e73e7f731cb00cbc4d384b8ab88578d9/Images/PCB_Image.png
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2020 Jiwoo Kim
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/Lowlevel/lowlevel.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 |
4 | uint16_t SO1 = 0;
5 | uint16_t SO2 = 0;
6 | uint16_t ADC3Raw[3];
7 | uint8_t adcIdx = 0;
8 |
9 | uint8_t SPIDataRx[2];
10 | uint8_t uartData;
11 |
12 | FIFO *uartFIFO;
13 | void (*Control)();
14 |
15 | uint16_t bufferCount = 0;
16 |
17 | uint8_t phaseOrder = 0;
18 |
19 | uint32_t timer = 0;
20 | uint8_t timerStatus = 0;
21 |
22 | void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
23 | {
24 | if (htim->Instance == TIM1)
25 | {
26 | __HAL_TIM_DISABLE_IT(&htim8, TIM_IT_UPDATE);
27 | __HAL_TIM_DISABLE(&htim8);
28 | __HAL_TIM_SET_COUNTER(&htim8, 0x0);
29 | __HAL_TIM_ENABLE_IT(&htim8, TIM_IT_UPDATE);
30 | __HAL_TIM_ENABLE(&htim8);
31 | }
32 | else if (htim->Instance == TIM8)
33 | {
34 | HAL_GPIO_TogglePin(TP1_GPIO_Port, TP1_Pin);
35 |
36 | if (phaseOrder)
37 | {
38 | SO1 = HAL_ADC_GetValue(&hadc1);
39 | SO2 = HAL_ADC_GetValue(&hadc2);
40 | }
41 | else
42 | {
43 | SO2 = HAL_ADC_GetValue(&hadc1);
44 | SO1 = HAL_ADC_GetValue(&hadc2);
45 | }
46 |
47 | ADC3Raw[adcIdx++] = HAL_ADC_GetValue(&hadc3);
48 | if (adcIdx >= 3)
49 | adcIdx = 0;
50 |
51 | Control();
52 |
53 | HAL_ADC_Start(&hadc1);
54 | HAL_ADC_Start(&hadc2);
55 | HAL_ADC_Start(&hadc3);
56 |
57 | HAL_GPIO_TogglePin(TP1_GPIO_Port, TP1_Pin);
58 | }
59 | }
60 |
61 | void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart)
62 | {
63 | HAL_GPIO_WritePin(ControlBus_TXEN_GPIO_Port, ControlBus_TXEN_Pin, GPIO_PIN_RESET);
64 | }
65 |
66 | void HAL_UART_RxCpltCallback(UART_HandleTypeDef *uartHandle)
67 | {
68 | uartFIFO->buffer[uartFIFO->topIdx++] = uartData;
69 |
70 | if (uartFIFO->topIdx >= UART_FIFO_BUFFER_SIZE)
71 | {
72 | uartFIFO->topIdx = 0;
73 | }
74 | HAL_UART_Receive_DMA(&huart2, &uartData, 1);
75 | }
76 |
77 | void _SendPacket(uint8_t *packet, uint32_t size)
78 | {
79 | HAL_GPIO_WritePin(ControlBus_TXEN_GPIO_Port, ControlBus_TXEN_Pin, GPIO_PIN_SET);
80 | HAL_UART_Transmit_IT(&huart2, packet, size);
81 | }
82 |
83 | void SetUartFIFO(FIFO *_uartFIFO)
84 | {
85 | uartFIFO = _uartFIFO;
86 | }
87 |
88 | void StartUartInterrupt()
89 | {
90 | HAL_UART_Receive_DMA(&huart2, &uartData, 1);
91 | }
92 |
93 | void StartOnBoardLED()
94 | {
95 | HAL_TIM_PWM_Start(&htim2, TIM_CHANNEL_4);
96 | }
97 |
98 | void SetOnBoardLED(uint32_t duty)
99 | {
100 | htim2.Instance->CCR4 = duty;
101 | }
102 |
103 | void SetControlFunc(void (*funcPtr)())
104 | {
105 | Control = funcPtr;
106 | }
107 |
108 | void StartControlTimer()
109 | {
110 | HAL_TIM_Base_Start_IT(&htim1);
111 | HAL_TIM_Base_Start_IT(&htim8);
112 | }
113 |
114 | void StartInverterPWM()
115 | {
116 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1);
117 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2);
118 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3);
119 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_1);
120 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_2);
121 | HAL_TIMEx_PWMN_Start(&htim1, TIM_CHANNEL_3);
122 | }
123 |
124 | void SetInverterPWMDuty(uint32_t aDuty, uint32_t bDuty, uint32_t cDuty)
125 | {
126 | if (phaseOrder)
127 | {
128 | TIM1->CCR1 = aDuty;
129 | TIM1->CCR2 = bDuty;
130 | TIM1->CCR3 = cDuty;
131 | }
132 | else
133 | {
134 | TIM1->CCR1 = bDuty;
135 | TIM1->CCR2 = aDuty;
136 | TIM1->CCR3 = cDuty;
137 | }
138 | }
139 |
140 | uint8_t GetUartData()
141 | {
142 | return uartData;
143 | }
144 |
145 | void StartADC()
146 | {
147 | HAL_ADC_Start(&hadc1);
148 | HAL_ADC_Start(&hadc2);
149 | HAL_ADC_Start(&hadc3);
150 | }
151 |
152 | uint16_t GetSO1()
153 | {
154 | return SO1;
155 | }
156 |
157 | uint16_t GetSO2()
158 | {
159 | return SO2;
160 | }
161 |
162 | uint16_t GetDCVoltageRaw()
163 | {
164 | return ADC3Raw[1];
165 | }
166 |
167 | uint16_t GetMotorTempRaw()
168 | {
169 | return ADC3Raw[2];
170 | }
171 |
172 | uint16_t GetFETTempRaw()
173 | {
174 | return ADC3Raw[0];
175 | }
176 |
177 | void OnGateDriver()
178 | {
179 | HAL_GPIO_WritePin(EN_GATE_GPIO_Port, EN_GATE_Pin, GPIO_PIN_SET);
180 | }
181 |
182 | void OffGateDriver()
183 | {
184 | HAL_GPIO_WritePin(EN_GATE_GPIO_Port, EN_GATE_Pin, GPIO_PIN_RESET);
185 | }
186 |
187 | uint8_t GateFault()
188 | {
189 | return !HAL_GPIO_ReadPin(nFAULT_GPIO_Port, nFAULT_Pin);
190 | }
191 |
192 | void ADCCalibration(uint8_t status)
193 | {
194 | if (status)
195 | {
196 | HAL_GPIO_WritePin(DC_CAL_GPIO_Port, DC_CAL_Pin, GPIO_PIN_SET);
197 | }
198 | else
199 | {
200 | HAL_GPIO_WritePin(DC_CAL_GPIO_Port, DC_CAL_Pin, GPIO_PIN_RESET);
201 | }
202 | }
203 |
204 | void SetPhaseOrder(uint8_t _phaseOrder)
205 | {
206 | phaseOrder = _phaseOrder;
207 | }
208 |
209 | void SPITransmitPool(uint8_t *dataTx, uint32_t len)
210 | {
211 | HAL_GPIO_WritePin(Encoder_CS_GPIO_Port, Encoder_CS_Pin, GPIO_PIN_SET);
212 | HAL_GPIO_WritePin(Encoder_CS_GPIO_Port, Encoder_CS_Pin, GPIO_PIN_RESET);
213 | HAL_SPI_TransmitReceive(&hspi2, dataTx, SPIDataRx, len, 1);
214 | }
215 |
216 | void SPITransmit(uint8_t *dataTx, uint32_t len)
217 | {
218 | HAL_GPIO_WritePin(Encoder_CS_GPIO_Port, Encoder_CS_Pin, GPIO_PIN_SET);
219 | HAL_GPIO_WritePin(Encoder_CS_GPIO_Port, Encoder_CS_Pin, GPIO_PIN_RESET);
220 | HAL_SPI_TransmitReceive_IT(&hspi2, dataTx, SPIDataRx, len);
221 | }
222 |
223 | uint8_t* SPIReceive()
224 | {
225 | return SPIDataRx;
226 | }
227 |
228 | void StartTimer()
229 | {
230 | timer = 0;
231 | timerStatus = 1;
232 | }
233 |
234 | uint32_t GetTimerTick()
235 | {
236 | return timer / 21;
237 | }
238 |
239 | void TimerUpdate()
240 | {
241 | if (timerStatus)
242 | {
243 | timer++;
244 | }
245 | }
246 |
247 | void ResetTimer()
248 | {
249 | timerStatus = 0;
250 | timer = 0;
251 | }
252 |
253 | uint32_t GetSector(uint32_t Address)
254 | {
255 | uint32_t sector = 0;
256 |
257 | if ((Address < ADDR_FLASH_SECTOR_1) && (Address >= ADDR_FLASH_SECTOR_0))
258 | {
259 | sector = FLASH_SECTOR_0;
260 | }
261 | else if ((Address < ADDR_FLASH_SECTOR_2) && (Address >= ADDR_FLASH_SECTOR_1))
262 | {
263 | sector = FLASH_SECTOR_1;
264 | }
265 | else if ((Address < ADDR_FLASH_SECTOR_3) && (Address >= ADDR_FLASH_SECTOR_2))
266 | {
267 | sector = FLASH_SECTOR_2;
268 | }
269 | else if ((Address < ADDR_FLASH_SECTOR_4) && (Address >= ADDR_FLASH_SECTOR_3))
270 | {
271 | sector = FLASH_SECTOR_3;
272 | }
273 | else if ((Address < ADDR_FLASH_SECTOR_5) && (Address >= ADDR_FLASH_SECTOR_4))
274 | {
275 | sector = FLASH_SECTOR_4;
276 | }
277 | else if ((Address < ADDR_FLASH_SECTOR_6) && (Address >= ADDR_FLASH_SECTOR_5))
278 | {
279 | sector = FLASH_SECTOR_5;
280 | }
281 | else if ((Address < ADDR_FLASH_SECTOR_7) && (Address >= ADDR_FLASH_SECTOR_6))
282 | {
283 | sector = FLASH_SECTOR_6;
284 | }
285 | else
286 | {
287 | sector = FLASH_SECTOR_7;
288 | }
289 |
290 | return sector;
291 | }
292 |
293 | void UnLockEEPROM()
294 | {
295 | FLASH_EraseInitTypeDef eraseInitStruct;
296 | uint32_t firstSector = 0;
297 | uint32_t nbOfSectors = 0;
298 | uint32_t sectorError = 0;
299 |
300 | firstSector = GetSector(ADDR_FLASH_SECTOR_7);
301 | nbOfSectors = GetSector(ADDR_FLASH_SECTOR_7) - firstSector + 1;
302 |
303 | eraseInitStruct.TypeErase = TYPEERASE_SECTORS;
304 | eraseInitStruct.VoltageRange = VOLTAGE_RANGE_3;
305 | eraseInitStruct.Sector = firstSector;
306 | eraseInitStruct.NbSectors = nbOfSectors;
307 |
308 | HAL_FLASH_Unlock();
309 |
310 | HAL_FLASHEx_Erase(&eraseInitStruct, §orError);
311 | }
312 |
313 | void WriteEEPROM(uint32_t address, uint32_t data)
314 | {
315 | HAL_FLASH_Program(TYPEPROGRAM_WORD, ADDR_FLASH_SECTOR_7 + (address * 4), data);
316 | }
317 |
318 | uint32_t ReadEEPROM(uint32_t address)
319 | {
320 | volatile uint32_t data = 0;
321 | uint32_t _address = ADDR_FLASH_SECTOR_7 + (address * 4);
322 |
323 | data = *(volatile uint32_t*) _address;
324 |
325 | return data;
326 | }
327 |
328 | void LockEEPROM()
329 | {
330 | HAL_FLASH_Lock();
331 | }
332 |
333 | void SetUartBuadRate(uint32_t buadRate)
334 | {
335 | huart2.Instance = USART2;
336 | huart2.Init.BaudRate = buadRate;
337 | huart2.Init.WordLength = UART_WORDLENGTH_8B;
338 | huart2.Init.StopBits = UART_STOPBITS_1;
339 | huart2.Init.Parity = UART_PARITY_NONE;
340 | huart2.Init.Mode = UART_MODE_TX_RX;
341 | huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
342 | huart2.Init.OverSampling = UART_OVERSAMPLING_16;
343 | HAL_UART_Init(&huart2);
344 | }
345 |
--------------------------------------------------------------------------------
/Lowlevel/lowlevel.hpp:
--------------------------------------------------------------------------------
1 | #ifndef LOWLEVEL_HPP_
2 | #define LOWLEVEL_HPP_
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 |
14 | #define ADDR_FLASH_SECTOR_0 ((uint32_t)0x08000000) /* Base @ of Sector 0, 16 Kbytes */
15 | #define ADDR_FLASH_SECTOR_1 ((uint32_t)0x08004000) /* Base @ of Sector 1, 16 Kbytes */
16 | #define ADDR_FLASH_SECTOR_2 ((uint32_t)0x08008000) /* Base @ of Sector 2, 16 Kbytes */
17 | #define ADDR_FLASH_SECTOR_3 ((uint32_t)0x0800C000) /* Base @ of Sector 3, 16 Kbytes */
18 | #define ADDR_FLASH_SECTOR_4 ((uint32_t)0x08010000) /* Base @ of Sector 4, 64 Kbytes */
19 | #define ADDR_FLASH_SECTOR_5 ((uint32_t)0x08020000) /* Base @ of Sector 5, 128 Kbytes */
20 | #define ADDR_FLASH_SECTOR_6 ((uint32_t)0x08040000) /* Base @ of Sector 6, 128 Kbytes */
21 | #define ADDR_FLASH_SECTOR_7 ((uint32_t)0x08060000) /* Base @ of Sector 7, 128 Kbytes */
22 |
23 | void StartOnBoardLED();
24 | void SetOnBoardLED(uint32_t duty);
25 |
26 | void SetControlFunc(void (*funcPtr)());
27 | void StartUartInterrupt();
28 | void StartControlTimer();
29 | void StartInverterPWM();
30 | void SetInverterPWMDuty(uint32_t aDuty, uint32_t bDuty, uint32_t cDuty);
31 | void StartEEPROM();
32 | void SetUartFIFO(FIFO * _uartFIFO);
33 |
34 | void _SendPacket(uint8_t *packet, uint32_t size);
35 | uint8_t GetUartData();
36 |
37 | void StartADC();
38 | uint16_t GetSO1();
39 | uint16_t GetSO2();
40 | uint16_t GetDCVoltageRaw();
41 | uint16_t GetMotorTempRaw();
42 | uint16_t GetFETTempRaw();
43 |
44 | void OnGateDriver();
45 | void OffGateDriver();
46 | uint8_t GateFault();
47 | void ADCCalibration(uint8_t status);
48 |
49 | void SetPhaseOrder(uint8_t _phaseOrder);
50 |
51 | void SPITransmitPool(uint8_t *dataTx, uint32_t len);
52 | void SPITransmit(uint8_t *dataTx, uint32_t len);
53 | uint8_t* SPIReceive();
54 |
55 | void StartTimer();
56 | uint32_t GetTimerTick();
57 | void TimerUpdate();
58 | void ResetTimer();
59 |
60 | uint32_t GetSector(uint32_t Address);
61 | void UnLockEEPROM();
62 | void WriteEEPROM(uint32_t address, uint32_t data);
63 | uint32_t ReadEEPROM(uint32_t address);
64 | void LockEEPROM();
65 |
66 | void SetUartBuadRate(uint32_t buadRate);
67 |
68 | #endif
69 |
--------------------------------------------------------------------------------
/MotorControl/motor_control.hpp:
--------------------------------------------------------------------------------
1 | #ifndef MOTOR_CONTROL_HPP_
2 | #define MOTOR_CONTROL_HPP_
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 | #include
11 | #include
12 |
13 | enum MotorControlMode
14 | {
15 | VOLTAGE_CONTROL_MODE,
16 | CURRENT_CONTROL_MODE,
17 | VELOCITY_CONTROL_MODE,
18 | POSITION_CONTROL_MODE,
19 | DAMPED_OSCILLATION_POSITION_CONTROL_MODE
20 | };
21 |
22 | struct ControlParam
23 | {
24 | uint8_t controlMode;
25 |
26 | float goalVoltage;
27 |
28 | float goalCurrent;
29 |
30 | float goalVelocity;
31 |
32 | float goalPosition;
33 | };
34 |
35 | struct DampedOscillationParam
36 | {
37 | float k;
38 | float x;
39 | float b;
40 | float xdot;
41 | float m;
42 | float _xddotBuff[10] = {0, };
43 | uint8_t _buffIdx = 0;
44 | float xddot;
45 | float F;
46 | };
47 |
48 | struct PIDParam
49 | {
50 | float error;
51 | float p;
52 | float i;
53 | float d;
54 | float a;
55 | float Kp;
56 | float Ki;
57 | float Kd;
58 | float Ka;
59 | };
60 |
61 | struct MotorParam
62 | {
63 | uint32_t polePair;
64 | float encoderOffset = 0.0f;
65 | };
66 |
67 | class MotorControl
68 | {
69 | public:
70 | void Init();
71 | void SetControlTable(ControlTable *_controlTable);
72 | void ControlUpdate();
73 |
74 | AS5047 Encoder = AS5047();
75 |
76 | LowPass filter_d = LowPass();
77 | LowPass filter_q = LowPass();
78 | LowPass filter_acceleration = LowPass();
79 |
80 | uint8_t controlMode = VOLTAGE_CONTROL_MODE;
81 |
82 | ControlParam controlParam;
83 |
84 | DampedOscillationParam dampedOscillationParam;
85 | PIDParam currentPIDParam_d;
86 | PIDParam currentPIDParam_q;
87 | PIDParam velocityPIDParam;
88 | PIDParam positionPIDParam;
89 | MotorParam motorParam;
90 |
91 | float supplyVoltage;
92 |
93 | int32_t ADC1Offset = 2047;
94 | int32_t ADC2Offset = 2047;
95 |
96 | float presentCurrent;
97 | float presentVoltage;
98 |
99 | float jointPosition;
100 | float rotorPosition;
101 | float extendedJointPosition;
102 | float jointVelocity;
103 |
104 | float velocityCommand;
105 | float currentCommand;
106 | float ia, ib, ic;
107 | float id, iq;
108 | float vd;
109 | float vq;
110 | float va, vb, vc;
111 | uint16_t aPWM, bPWM, cPWM;
112 |
113 | private:
114 | ControlTable *controlTable;
115 |
116 | void DampedOscillationPositionControl();
117 | void PositionControl();
118 | void VelocityControl();
119 | void CurrentControl();
120 | void VoltageControl();
121 |
122 | void DQZTrans(float a, float b, float c, float theta, float *d, float *q);
123 | void DQZTransInv(float d, float q, float theta, float *a, float *b, float *c);
124 | };
125 |
126 | #endif
127 |
--------------------------------------------------------------------------------
/Protection/protection.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | void Protection::Init()
4 | {
5 | voltageErrorHigh = supplyVoltage + SUPPLY_PROTECTION;
6 | voltageErrorLow = supplyVoltage - SUPPLY_PROTECTION;
7 | }
8 |
9 | void Protection::Update()
10 | {
11 | supplyVoltage = GetDCVoltageRaw() * DC_VOLTAGE_COEFF;
12 |
13 | if (controlTable->controlTableData[15].data >= 1)
14 | {
15 | if (supplyVoltage <= *(float*) &controlTable->controlTableData[16].data)
16 | {
17 | controlTable->controlTableData[31].data |= BATTERY_VOLTAGE_ERROR_MASK;
18 | controlTable->SetTable(29, 0, 1);
19 | //Battery Voltage Error
20 | }
21 | else
22 | {
23 | controlTable->controlTableData[31].data &= BATTERY_VOLTAGE_ERROR_MASK;
24 | }
25 | }
26 | else
27 | {
28 | if (controlTable->controlTableData[5].data == 1)
29 | {
30 | if (supplyVoltage <= voltageErrorLow)
31 | {
32 | controlTable->controlTableData[31].data |= VOLTAGE_ERROR_MASK;
33 | controlTable->SetTable(29, 0, 1);
34 | //Voltage Error
35 | }
36 | else
37 | {
38 | controlTable->controlTableData[31].data &= VOLTAGE_ERROR_MASK;
39 | }
40 | }
41 | else if (controlTable->controlTableData[5].data == 2)
42 | {
43 | if (supplyVoltage <= voltageErrorLow || supplyVoltage >= voltageErrorHigh)
44 | {
45 | controlTable->controlTableData[31].data |= VOLTAGE_ERROR_MASK;
46 | controlTable->SetTable(29, 0, 1);
47 | //Voltage Error
48 | }
49 | else
50 | {
51 | controlTable->controlTableData[31].data &= VOLTAGE_ERROR_MASK;
52 | }
53 | }
54 | }
55 |
56 | if (GateFault())
57 | {
58 | controlTable->controlTableData[31].data |= ELECTRICAL_SHOCK_ERROR_MASK;
59 | controlTable->SetTable(29, 0, 1);
60 | //Electrical Shock Error
61 | }
62 | else
63 | {
64 | controlTable->controlTableData[31].data &= ELECTRICAL_SHOCK_ERROR_MASK;
65 | }
66 |
67 | if (GetFETTempRaw() * ONBOARD_TEMP_COEFF >= *(float*) &controlTable->controlTableData[10].data)
68 | {
69 | controlTable->controlTableData[31].data |= BOARD_TEMPERATURE_ERROR_MASK;
70 | //Board Temperature Error
71 | }
72 | else
73 | {
74 | controlTable->controlTableData[31].data &= BOARD_TEMPERATURE_ERROR_MASK;
75 | }
76 |
77 | if (GetMotorTempRaw() >= controlTable->controlTableData[11].data)
78 | {
79 | controlTable->controlTableData[31].data |= MOTOR_TEMPERATURE_ERROR_MASK;
80 | //Motor Temperature Error
81 | }
82 | else
83 | {
84 | controlTable->controlTableData[31].data &= MOTOR_TEMPERATURE_ERROR_MASK;
85 | }
86 | }
87 |
88 | void Protection::SetControlTable(ControlTable *_controlTable)
89 | {
90 | controlTable = _controlTable;
91 | }
92 |
--------------------------------------------------------------------------------
/Protection/protection.hpp:
--------------------------------------------------------------------------------
1 | #ifndef PROTECTION_HPP_
2 | #define PROTECTION_HPP_
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 | #include
10 |
11 | extern uint8_t controlStatus;
12 |
13 | class Protection
14 | {
15 | public:
16 | void Update();
17 | void Init();
18 |
19 | float supplyVoltage = 0.0f;
20 |
21 | void SetControlTable(ControlTable *_controlTable);
22 |
23 | private:
24 | ControlTable *controlTable;
25 |
26 | float voltageErrorHigh;
27 | float voltageErrorLow;
28 | };
29 |
30 | #endif
31 |
--------------------------------------------------------------------------------
/Protocol/controlTable.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | void ControlTable::Init()
4 | {
5 | uint16_t address = 0;
6 |
7 | InitTable(address++, MODEL_NUMBER, R, 2, INT, FIXED); //Model Number
8 | InitTable(address++, ((FW_VER_MAJOR << 4) | FW_VER_MINOR), R, 1, INT, FIXED); //Firmware Version
9 | InitTable(address++, 1, RW, 1, INT, EEPROM); //ID
10 | InitTable(address++, 3, RW, 1, INT, EEPROM); //Baud Rate
11 | InitTable(address++, 250, RW, 1, INT, EEPROM); //Return Delay Time
12 | InitTable(address++, 1, RW, 1, INT, EEPROM); //Voltage Protection Mode
13 | InitTable(address++, 4, RW, 1, INT, EEPROM); //Operating Mode
14 | InitTable(address++, 255, RW, 1, INT, EEPROM); //Secondary ID
15 | InitTable(address++, 0x00000000, RW, 4, FLOAT, EEPROM); //Homing Offset
16 | InitTable(address++, 0x3F000000, RW, 4, FLOAT, EEPROM); //Moving Threshold
17 | InitTable(address++, 0x42A00000, RW, 4, FLOAT, EEPROM); //Board Temperature Limit
18 | InitTable(address++, 0x00000000, RW, 4, FLOAT, EEPROM); //Motor Temperature Limit
19 | InitTable(address++, 0x41F00000, RW, 4, FLOAT, EEPROM); //Max Voltage Limit
20 | InitTable(address++, 0x41000000, RW, 4, FLOAT, EEPROM); //Min Voltage Limit
21 | InitTable(address++, 0, RW, 1, INT, EEPROM); //Shutdown
22 | InitTable(address++, 0, RW, 1, INT, EEPROM); //Battery Mode
23 | InitTable(address++, 0x41A80000, RW, 4, FLOAT, EEPROM); //Battery Cutoff Voltage
24 | InitTable(address++, 0x41A00000, RW, 4, FLOAT, EEPROM); //Current I Gain
25 | InitTable(address++, 0x40C00000, RW, 4, FLOAT, EEPROM); //Current P Gain
26 | InitTable(address++, 0x3C23D70A, RW, 4, FLOAT, EEPROM); //Velocity I Gain
27 | InitTable(address++, 0x3BA3D70A, RW, 4, FLOAT, EEPROM); //Velocity P Gain
28 | InitTable(address++, 0x00000000, RW, 4, FLOAT, EEPROM); //Position I Gain
29 | InitTable(address++, 0x41200000, RW, 4, FLOAT, EEPROM); //Position P Gain
30 | InitTable(address++, 0x00000000, RW, 1, INT, EEPROM); //Phase Order
31 | InitTable(address++, 0, RW, 4, INT, EEPROM); //ADC1 Offset
32 | InitTable(address++, 0, RW, 4, INT, EEPROM); //ADC2 Offset
33 | InitTable(address++, 0x00000000, RW, 4, FLOAT, EEPROM); //Encoder Offset
34 | InitTable(address++, 7, RW, 1, INT, EEPROM); //Pole Pair
35 |
36 | InitTable(address++, 0, RW, 1, INT, RAM); //Inverter Enable
37 | InitTable(address++, 0, RW, 1, INT, RAM); //Torque Enable
38 | InitTable(address++, 0, R, 1, INT, RAM); //Registered Instruction
39 | InitTable(address++, 0, R, 1, INT, RAM); //Hardware Error Status
40 | InitTable(address++, 0, RW, 1, INT, RAM); //Bus Watchdog
41 | InitTable(address++, 0x3DCCCCCD, RW, 4, FLOAT, RAM); //Goal PWM
42 | InitTable(address++, 0x3F000000, RW, 4, FLOAT, RAM); //Goal Current
43 | InitTable(address++, 0x42200000, RW, 4, FLOAT, RAM); //Goal Velocity
44 | InitTable(address++, 0x00000000, RW, 4, FLOAT, RAM); //Goal Position
45 | InitTable(address++, 0x3C23D70A, RW, 4, FLOAT, RAM); //Stiffness
46 | InitTable(address++, 0x00000000, RW, 4, FLOAT, RAM); //Friction
47 | InitTable(address++, 0x00000000, RW, 4, FLOAT, RAM); //Inertia
48 | InitTable(address++, 0, R, 2, INT, RAM); //Realtime Tick
49 | InitTable(address++, 0, R, 1, INT, RAM); //Moving
50 | InitTable(address++, 0, R, 1, INT, RAM); //Moving Status
51 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present PWM
52 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present Current
53 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present Velocity
54 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present Position
55 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present Input Voltage
56 | InitTable(address++, 0x00000000, R, 4, FLOAT, RAM); //Present Board Temperature
57 | InitTable(address++, 0, R, 4, INT, RAM); //Present Motor Temperature
58 | InitTable(address++, 0, RW, 1, INT, RAM); //Calibration
59 | InitTable(address++, 0x3D4CCCCD, RW, 4, FLOAT, RAM); //Calibration PWM
60 | }
61 |
62 | void ControlTable::LoadControlTableFromEEPROM()
63 | {
64 | for (uint32_t address = 0; address < CONTROLTABLE_EEPROM_END_ADDRESS + 1; address++)
65 | {
66 | controlTableData[address].data = ReadEEPROM(address);
67 | }
68 | }
69 |
70 | void ControlTable::FactoryReset()
71 | {
72 | UnLockEEPROM();
73 | for (uint32_t address = 0; address < CONTROLTABLE_EEPROM_END_ADDRESS + 1; address++)
74 | {
75 | WriteEEPROM((uint32_t) address, controlTableData[address].initialValue);
76 | }
77 | LockEEPROM();
78 | }
79 |
80 | uint8_t ControlTable::SetTable(uint16_t address, uint32_t data, uint8_t len)
81 | {
82 | if (controlTableData[29].data != 0 && controlTableData[28].data != 0 && controlTableData[address].location == EEPROM)
83 | {
84 | return 1;
85 | }
86 |
87 | if (address > CONTROLTABLE_END_ADDRESS)
88 | {
89 | return 1;
90 | }
91 |
92 | if (len < controlTableData[address].len)
93 | {
94 | return 2;
95 | }
96 | else if (controlTableData[address].access == R)
97 | {
98 | return 1;
99 | }
100 | else
101 | {
102 | controlTableData[address].data = data;
103 |
104 | if (controlTableData[address].location == EEPROM)
105 | {
106 | UnLockEEPROM();
107 | for (uint32_t _address = 0; _address < CONTROLTABLE_EEPROM_END_ADDRESS + 1; _address++)
108 | {
109 | WriteEEPROM((uint32_t) _address, controlTableData[_address].data);
110 | }
111 | LockEEPROM();
112 |
113 | if (address == 3)
114 | {
115 | HAL_NVIC_SystemReset();
116 | }
117 | }
118 | return 0;
119 | }
120 | }
121 |
122 | uint8_t ControlTable::GetTable(uint16_t address, uint32_t *data, uint8_t len)
123 | {
124 | if (address > CONTROLTABLE_END_ADDRESS)
125 | {
126 | return 1;
127 | }
128 | else
129 | {
130 | *data = controlTableData[address].data;
131 | return 0;
132 | }
133 | }
134 |
135 | void ControlTable::InitTable(uint16_t address, uint32_t initialValue, uint8_t access, uint8_t len, uint8_t type, uint8_t location)
136 | {
137 | controlTableData[address].initialValue = initialValue;
138 | controlTableData[address].data = initialValue;
139 | controlTableData[address].access = access;
140 | controlTableData[address].len = len;
141 | controlTableData[address].location = location;
142 | controlTableData[address].type = type;
143 | }
144 |
--------------------------------------------------------------------------------
/Protocol/controlTable.hpp:
--------------------------------------------------------------------------------
1 | #ifndef CONTROLTABLE_HPP_
2 | #define CONTROLTABLE_HPP_
3 |
4 | #include
5 | #include
6 | #include
7 |
8 | enum Access
9 | {
10 | R,
11 | RW
12 | };
13 |
14 | enum DataType
15 | {
16 | INT,
17 | FLOAT
18 | };
19 |
20 | enum DataLocation
21 | {
22 | EEPROM,
23 | RAM,
24 | FIXED
25 | };
26 |
27 | struct ControlTableData
28 | {
29 | uint32_t data = 0x0000;
30 | uint32_t initialValue = 0x0000;
31 | uint8_t access = R;
32 | uint8_t len = 1;
33 | uint8_t type = INT;
34 | uint8_t location = EEPROM;
35 | };
36 |
37 | class ControlTable
38 | {
39 | public:
40 | ControlTableData controlTableData[52];
41 |
42 | void Init();
43 | void LoadControlTableFromEEPROM();
44 | void FactoryReset();
45 | uint8_t SetTable(uint16_t address, uint32_t data, uint8_t len);
46 | uint8_t GetTable(uint16_t address, uint32_t *data, uint8_t len);
47 |
48 | private:
49 | void InitTable(uint16_t address, uint32_t initialValue, uint8_t access, uint8_t len, uint8_t type, uint8_t location);
50 | };
51 |
52 | #endif
53 |
--------------------------------------------------------------------------------
/Protocol/fifo.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 |
4 | uint8_t FIFO::pop()
5 | {
6 | uint8_t data = buffer[bottomIdx++];
7 |
8 | if (bottomIdx >= UART_FIFO_BUFFER_SIZE)
9 | {
10 | bottomIdx = 0;
11 | }
12 |
13 | return data;
14 | }
15 |
--------------------------------------------------------------------------------
/Protocol/fifo.hpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 |
4 | #ifndef FIFO_HPP_
5 | #define FIFO_HPP_
6 |
7 | class FIFO
8 | {
9 | public:
10 | uint8_t pop();
11 |
12 | uint32_t topIdx = 0;
13 | uint32_t bottomIdx = 0;
14 |
15 | uint8_t buffer[UART_FIFO_BUFFER_SIZE];
16 | private:
17 |
18 | };
19 |
20 | #endif
21 |
--------------------------------------------------------------------------------
/Protocol/protocol.hpp:
--------------------------------------------------------------------------------
1 | #ifndef PROTOCOL_HPP_
2 | #define PROTOCOL_HPP_
3 |
4 | #include
5 | #include
6 | #include
7 | #include
8 | #include
9 |
10 | #define DXL_MAKEWORD(a, b) ((uint16_t)(((uint8_t)(((uint64_t)(a)) & 0xff)) | ((uint16_t)((uint8_t)(((uint64_t)(b)) & 0xff))) << 8))
11 | #define DXL_MAKEDWORD(a, b) ((uint32_t)(((uint16_t)(((uint64_t)(a)) & 0xffff)) | ((uint32_t)((uint16_t)(((uint64_t)(b)) & 0xffff))) << 16))
12 | #define DXL_LOWORD(l) ((uint16_t)(((uint64_t)(l)) & 0xffff))
13 | #define DXL_HIWORD(l) ((uint16_t)((((uint64_t)(l)) >> 16) & 0xffff))
14 | #define DXL_LOBYTE(w) ((uint8_t)(((uint64_t)(w)) & 0xff))
15 | #define DXL_HIBYTE(w) ((uint8_t)((((uint64_t)(w)) >> 8) & 0xff))
16 |
17 | #define INST_PING 0x1
18 | #define INST_READ 0x2
19 | #define INST_WRITE 0x3
20 | #define INST_REG_WRITE 0x4
21 | #define INST_ACTION 0x5
22 | #define INST_FACTORY_RESET 0x6
23 | #define INST_SYNC_WRITE 0x83
24 | #define INST_BULK_READ 0x92
25 | #define INST_REBOOT 0x8
26 | #define INST_CLEAR 0x10
27 | #define INST_STATUS 0x55
28 | #define INST_SYNC_READ 0x82
29 | #define INST_BULK_WRITE 0x93
30 |
31 | #define ERROR_NONE 0x00
32 | #define ERROR_INST 0x02
33 | #define ERROR_CRC 0x03
34 | #define ERROR_DATA_LENGTH 0x05
35 | #define ERROR_ACCESS 0x07
36 |
37 | #define PKT_HEADER0 0
38 | #define PKT_HEADER1 1
39 | #define PKT_HEADER2 2
40 | #define PKT_RESERVED 3
41 | #define PKT_ID 4
42 | #define PKT_LENGTH_L 5
43 | #define PKT_LENGTH_H 6
44 | #define PKT_INSTRUCTION 7
45 | #define PKT_ERROR 8
46 | #define PKT_PARAMETER0 8
47 |
48 | #define RXPACKET_MAX_LEN 1024
49 |
50 | class Protocol
51 | {
52 | public:
53 | FIFO uartFIFO = FIFO();
54 | ControlTable controlTable = ControlTable();
55 | void Update();
56 |
57 | private:
58 | uint8_t rxPacket[RXPACKET_MAX_LEN];
59 | uint8_t txPacket[RXPACKET_MAX_LEN];
60 |
61 | uint32_t rxLength = 0;
62 | uint32_t waitLength = 10;
63 | uint32_t ReadPort(uint8_t *packet, uint32_t length);
64 | int8_t RxPacket();
65 | int8_t CheckID(uint8_t packetID);
66 | void RunInstruction();
67 |
68 | void InstPing();
69 | void InstRead();
70 | void InstWrite();
71 |
72 | int16_t txParamIdx = 0;
73 | void InitTx();
74 | void SetErrorCode(uint8_t errorCode);
75 | void AddTxParam(uint8_t data);
76 | void SendPacket();
77 |
78 | void AddStuffing(uint8_t *packet);
79 | void RemoveStuffing(uint8_t *packet);
80 | uint16_t CRC16(uint16_t crcAccum, uint8_t *dataBlkPtr, uint16_t dataBlkSize);
81 |
82 | };
83 |
84 | #endif
85 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | J-Drive
2 | =============
3 | FOC Based High Performance BLDC Servo Driver
4 |
5 |
6 |
--------------------------------------------------------------------------------
/STM32F446RETX_FLASH.ld:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file LinkerScript.ld
4 | * @author Auto-generated by STM32CubeIDE
5 | * Abstract : Linker script for NUCLEO-F446RE Board embedding STM32F446RETx Device from stm32f4 series
6 | * 512Kbytes FLASH
7 | * 128Kbytes RAM
8 | *
9 | * Set heap size, stack size and stack location according
10 | * to application requirements.
11 | *
12 | * Set memory bank area and size if external memory is used
13 | ******************************************************************************
14 | * @attention
15 | *
16 | * © Copyright (c) 2020 STMicroelectronics.
17 | * All rights reserved.
18 | *
19 | * This software component is licensed by ST under BSD 3-Clause license,
20 | * the "License"; You may not use this file except in compliance with the
21 | * License. You may obtain a copy of the License at:
22 | * opensource.org/licenses/BSD-3-Clause
23 | *
24 | ******************************************************************************
25 | */
26 |
27 | /* Entry Point */
28 | ENTRY(Reset_Handler)
29 |
30 | /* Highest address of the user mode stack */
31 | _estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
32 |
33 | _Min_Heap_Size = 0xf00 ; /* required amount of heap */
34 | _Min_Stack_Size = 0xf00 ; /* required amount of stack */
35 |
36 | /* Memories definition */
37 | MEMORY
38 | {
39 | RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
40 | FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K
41 | }
42 |
43 | /* Sections */
44 | SECTIONS
45 | {
46 | /* The startup code into "FLASH" Rom type memory */
47 | .isr_vector :
48 | {
49 | . = ALIGN(4);
50 | KEEP(*(.isr_vector)) /* Startup code */
51 | . = ALIGN(4);
52 | } >FLASH
53 |
54 | /* The program code and other data into "FLASH" Rom type memory */
55 | .text :
56 | {
57 | . = ALIGN(4);
58 | *(.text) /* .text sections (code) */
59 | *(.text*) /* .text* sections (code) */
60 | *(.glue_7) /* glue arm to thumb code */
61 | *(.glue_7t) /* glue thumb to arm code */
62 | *(.eh_frame)
63 |
64 | KEEP (*(.init))
65 | KEEP (*(.fini))
66 |
67 | . = ALIGN(4);
68 | _etext = .; /* define a global symbols at end of code */
69 | } >FLASH
70 |
71 | /* Constant data into "FLASH" Rom type memory */
72 | .rodata :
73 | {
74 | . = ALIGN(4);
75 | *(.rodata) /* .rodata sections (constants, strings, etc.) */
76 | *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
77 | . = ALIGN(4);
78 | } >FLASH
79 |
80 | .ARM.extab : {
81 | . = ALIGN(4);
82 | *(.ARM.extab* .gnu.linkonce.armextab.*)
83 | . = ALIGN(4);
84 | } >FLASH
85 |
86 | .ARM : {
87 | . = ALIGN(4);
88 | __exidx_start = .;
89 | *(.ARM.exidx*)
90 | __exidx_end = .;
91 | . = ALIGN(4);
92 | } >FLASH
93 |
94 | .preinit_array :
95 | {
96 | . = ALIGN(4);
97 | PROVIDE_HIDDEN (__preinit_array_start = .);
98 | KEEP (*(.preinit_array*))
99 | PROVIDE_HIDDEN (__preinit_array_end = .);
100 | . = ALIGN(4);
101 | } >FLASH
102 |
103 | .init_array :
104 | {
105 | . = ALIGN(4);
106 | PROVIDE_HIDDEN (__init_array_start = .);
107 | KEEP (*(SORT(.init_array.*)))
108 | KEEP (*(.init_array*))
109 | PROVIDE_HIDDEN (__init_array_end = .);
110 | . = ALIGN(4);
111 | } >FLASH
112 |
113 | .fini_array :
114 | {
115 | . = ALIGN(4);
116 | PROVIDE_HIDDEN (__fini_array_start = .);
117 | KEEP (*(SORT(.fini_array.*)))
118 | KEEP (*(.fini_array*))
119 | PROVIDE_HIDDEN (__fini_array_end = .);
120 | . = ALIGN(4);
121 | } >FLASH
122 |
123 | /* Used by the startup to initialize data */
124 | _sidata = LOADADDR(.data);
125 |
126 | /* Initialized data sections into "RAM" Ram type memory */
127 | .data :
128 | {
129 | . = ALIGN(4);
130 | _sdata = .; /* create a global symbol at data start */
131 | *(.data) /* .data sections */
132 | *(.data*) /* .data* sections */
133 |
134 | . = ALIGN(4);
135 | _edata = .; /* define a global symbol at data end */
136 |
137 | } >RAM AT> FLASH
138 |
139 | /* Uninitialized data section into "RAM" Ram type memory */
140 | . = ALIGN(4);
141 | .bss :
142 | {
143 | /* This is used by the startup in order to initialize the .bss section */
144 | _sbss = .; /* define a global symbol at bss start */
145 | __bss_start__ = _sbss;
146 | *(.bss)
147 | *(.bss*)
148 | *(COMMON)
149 |
150 | . = ALIGN(4);
151 | _ebss = .; /* define a global symbol at bss end */
152 | __bss_end__ = _ebss;
153 | } >RAM
154 |
155 | /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
156 | ._user_heap_stack :
157 | {
158 | . = ALIGN(8);
159 | PROVIDE ( end = . );
160 | PROVIDE ( _end = . );
161 | . = . + _Min_Heap_Size;
162 | . = . + _Min_Stack_Size;
163 | . = ALIGN(8);
164 | } >RAM
165 |
166 | /* Remove information from the compiler libraries */
167 | /DISCARD/ :
168 | {
169 | libc.a ( * )
170 | libm.a ( * )
171 | libgcc.a ( * )
172 | }
173 |
174 | .ARM.attributes 0 : { *(.ARM.attributes) }
175 | }
176 |
--------------------------------------------------------------------------------
/STM32F446RETX_RAM.ld:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file LinkerScript.ld
4 | * @author Auto-generated by STM32CubeIDE
5 | * Abstract : Linker script for NUCLEO-F446RE Board embedding STM32F446RETx Device from stm32f4 series
6 | * 512Kbytes FLASH
7 | * 128Kbytes RAM
8 | *
9 | * Set heap size, stack size and stack location according
10 | * to application requirements.
11 | *
12 | * Set memory bank area and size if external memory is used
13 | ******************************************************************************
14 | * @attention
15 | *
16 | * © Copyright (c) 2020 STMicroelectronics.
17 | * All rights reserved.
18 | *
19 | * This software component is licensed by ST under BSD 3-Clause license,
20 | * the "License"; You may not use this file except in compliance with the
21 | * License. You may obtain a copy of the License at:
22 | * opensource.org/licenses/BSD-3-Clause
23 | *
24 | ******************************************************************************
25 | */
26 |
27 | /* Entry Point */
28 | ENTRY(Reset_Handler)
29 |
30 | /* Highest address of the user mode stack */
31 | _estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
32 |
33 | _Min_Heap_Size = 0x200; /* required amount of heap */
34 | _Min_Stack_Size = 0x400; /* required amount of stack */
35 |
36 | /* Memories definition */
37 | MEMORY
38 | {
39 | RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
40 | FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 512K
41 | }
42 |
43 | /* Sections */
44 | SECTIONS
45 | {
46 | /* The startup code into "RAM" Ram type memory */
47 | .isr_vector :
48 | {
49 | . = ALIGN(4);
50 | KEEP(*(.isr_vector)) /* Startup code */
51 | . = ALIGN(4);
52 | } >RAM
53 |
54 | /* The program code and other data into "RAM" Ram type memory */
55 | .text :
56 | {
57 | . = ALIGN(4);
58 | *(.text) /* .text sections (code) */
59 | *(.text*) /* .text* sections (code) */
60 | *(.glue_7) /* glue arm to thumb code */
61 | *(.glue_7t) /* glue thumb to arm code */
62 | *(.eh_frame)
63 |
64 | KEEP (*(.init))
65 | KEEP (*(.fini))
66 |
67 | . = ALIGN(4);
68 | _etext = .; /* define a global symbols at end of code */
69 | } >RAM
70 |
71 | /* Constant data into "RAM" Ram type memory */
72 | .rodata :
73 | {
74 | . = ALIGN(4);
75 | *(.rodata) /* .rodata sections (constants, strings, etc.) */
76 | *(.rodata*) /* .rodata* sections (constants, strings, etc.) */
77 | . = ALIGN(4);
78 | } >RAM
79 |
80 | .ARM.extab : {
81 | . = ALIGN(4);
82 | *(.ARM.extab* .gnu.linkonce.armextab.*)
83 | . = ALIGN(4);
84 | } >RAM
85 |
86 | .ARM : {
87 | . = ALIGN(4);
88 | __exidx_start = .;
89 | *(.ARM.exidx*)
90 | __exidx_end = .;
91 | . = ALIGN(4);
92 | } >RAM
93 |
94 | .preinit_array :
95 | {
96 | . = ALIGN(4);
97 | PROVIDE_HIDDEN (__preinit_array_start = .);
98 | KEEP (*(.preinit_array*))
99 | PROVIDE_HIDDEN (__preinit_array_end = .);
100 | . = ALIGN(4);
101 | } >RAM
102 |
103 | .init_array :
104 | {
105 | . = ALIGN(4);
106 | PROVIDE_HIDDEN (__init_array_start = .);
107 | KEEP (*(SORT(.init_array.*)))
108 | KEEP (*(.init_array*))
109 | PROVIDE_HIDDEN (__init_array_end = .);
110 | . = ALIGN(4);
111 | } >RAM
112 |
113 | .fini_array :
114 | {
115 | . = ALIGN(4);
116 | PROVIDE_HIDDEN (__fini_array_start = .);
117 | KEEP (*(SORT(.fini_array.*)))
118 | KEEP (*(.fini_array*))
119 | PROVIDE_HIDDEN (__fini_array_end = .);
120 | . = ALIGN(4);
121 | } >RAM
122 |
123 | /* Used by the startup to initialize data */
124 | _sidata = LOADADDR(.data);
125 |
126 | /* Initialized data sections into "RAM" Ram type memory */
127 | .data :
128 | {
129 | . = ALIGN(4);
130 | _sdata = .; /* create a global symbol at data start */
131 | *(.data) /* .data sections */
132 | *(.data*) /* .data* sections */
133 |
134 | . = ALIGN(4);
135 | _edata = .; /* define a global symbol at data end */
136 |
137 | } >RAM
138 |
139 | /* Uninitialized data section into "RAM" Ram type memory */
140 | . = ALIGN(4);
141 | .bss :
142 | {
143 | /* This is used by the startup in order to initialize the .bss section */
144 | _sbss = .; /* define a global symbol at bss start */
145 | __bss_start__ = _sbss;
146 | *(.bss)
147 | *(.bss*)
148 | *(COMMON)
149 |
150 | . = ALIGN(4);
151 | _ebss = .; /* define a global symbol at bss end */
152 | __bss_end__ = _ebss;
153 | } >RAM
154 |
155 | /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
156 | ._user_heap_stack :
157 | {
158 | . = ALIGN(8);
159 | PROVIDE ( end = . );
160 | PROVIDE ( _end = . );
161 | . = . + _Min_Heap_Size;
162 | . = . + _Min_Stack_Size;
163 | . = ALIGN(8);
164 | } >RAM
165 |
166 | /* Remove information from the compiler libraries */
167 | /DISCARD/ :
168 | {
169 | libc.a ( * )
170 | libm.a ( * )
171 | libgcc.a ( * )
172 | }
173 |
174 | .ARM.attributes 0 : { *(.ARM.attributes) }
175 | }
176 |
--------------------------------------------------------------------------------
/Util/util.cpp:
--------------------------------------------------------------------------------
1 | #include
2 |
3 | void Delaymillis(uint32_t ms)
4 | {
5 | HAL_Delay(ms);
6 | }
7 |
8 | float Limiter(float value, float limit)
9 | {
10 | if (value > limit)
11 | {
12 | return limit;
13 | }
14 | else if (value < -limit)
15 | {
16 | return -limit;
17 | }
18 |
19 | return value;
20 | }
21 |
--------------------------------------------------------------------------------
/Util/util.hpp:
--------------------------------------------------------------------------------
1 | #ifndef UTIL_HPP_
2 | #define UTIL_HPP_
3 |
4 | #include
5 | #include
6 |
7 | void Delaymillis(uint32_t ms);
8 | float Limiter(float value, float limit);
9 |
10 | #endif
11 |
--------------------------------------------------------------------------------