├── .gitignore ├── FOC ├── sensor │ ├── AS5600.c │ ├── AS5600.h │ ├── current_sense.h │ └── current_sense.c ├── hardware_specific │ ├── stm32_mcu.h │ └── stm32_mcu.c ├── FOC_LPF.h ├── hardware_api.h ├── FOC_conf.h ├── FOC_PID.h ├── FOC_LPF.c ├── FOC.h ├── FOC_utils.h ├── FOC_utils.c ├── FOC_PID.c └── FOC.c ├── .idea ├── FOC_Driver.iml ├── misc.xml ├── vcs.xml ├── modules.xml └── encodings.xml ├── Drivers ├── CMSIS │ ├── Device │ │ └── ST │ │ │ └── STM32F1xx │ │ │ └── Include │ │ │ ├── stm32f1xx.h │ │ │ ├── stm32f103xb.h │ │ │ └── system_stm32f1xx.h │ └── Include │ │ ├── cmsis_version.h │ │ └── tz_context.h └── STM32F1xx_HAL_Driver │ ├── License.md │ ├── Src │ └── stm32f1xx_hal_gpio_ex.c │ └── Inc │ └── stm32f1xx_hal_def.h ├── Middlewares └── Third_Party │ └── FreeRTOS │ └── Source │ ├── CMSIS_RTOS │ ├── cmsis_os.c │ └── cmsis_os.h │ ├── include │ ├── projdefs.h │ ├── stack_macros.h │ ├── StackMacros.h │ ├── portable.h │ └── deprecated_definitions.h │ ├── list.c │ └── portable │ └── GCC │ └── ARM_CM3 │ └── portmacro.h ├── config └── daplink_config.cfg ├── Core ├── Src │ ├── retarget.c │ ├── stm32f1xx_hal_msp.c │ ├── gpio.c │ ├── sysmem.c │ ├── syscalls.c │ ├── i2c.c │ ├── spi.c │ ├── can.c │ ├── usart.c │ ├── adc.c │ ├── stm32f1xx_hal_timebase_tim.c │ ├── tim.c │ ├── stm32f1xx_it.c │ └── main.c └── Inc │ ├── gpio.h │ ├── adc.h │ ├── can.h │ ├── i2c.h │ ├── spi.h │ ├── usart.h │ ├── tim.h │ ├── stm32f1xx_it.h │ ├── main.h │ └── FreeRTOSConfig.h ├── GUI ├── st7735 │ ├── image.h │ ├── fonts.h │ └── st7735.h ├── gui.h └── gui.c ├── BSP ├── bsp_button.h └── bsp_button.c ├── .project ├── CMakeLists_template.txt ├── CMakeLists.txt └── STM32F103CBTX_FLASH.ld /.gitignore: -------------------------------------------------------------------------------- 1 | # 项目排除路径 2 | /cmake-build-debug/ -------------------------------------------------------------------------------- /FOC/sensor/AS5600.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/FOC/sensor/AS5600.c -------------------------------------------------------------------------------- /FOC/sensor/AS5600.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/FOC/sensor/AS5600.h -------------------------------------------------------------------------------- /.idea/FOC_Driver.iml: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f1xx.h -------------------------------------------------------------------------------- /.idea/misc.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/Drivers/CMSIS/Device/ST/STM32F1xx/Include/stm32f103xb.h -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.c: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.c -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Aiano/FOC_Driver/HEAD/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h -------------------------------------------------------------------------------- /.idea/vcs.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | -------------------------------------------------------------------------------- /config/daplink_config.cfg: -------------------------------------------------------------------------------- 1 | # 选择下载器 2 | interface cmsis-dap 3 | transport select swd 4 | # 选择板子 5 | set WORKAREASIZE 0x5000 6 | set FLASH_SIZE 0x20000 7 | 8 | source [find target/stm32f1x.cfg] 9 | adapter speed 10000 -------------------------------------------------------------------------------- /FOC/sensor/current_sense.h: -------------------------------------------------------------------------------- 1 | #ifndef FOC_DRIVER_CURRENT_SENSE_H 2 | #define FOC_DRIVER_CURRENT_SENSE_H 3 | #include "main.h" 4 | 5 | extern float cs_value[3]; 6 | 7 | void cs_init(); 8 | uint8_t cs_get_value(); 9 | #endif //FOC_DRIVER_CURRENT_SENSE_H 10 | -------------------------------------------------------------------------------- /.idea/modules.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /Core/Src/retarget.c: -------------------------------------------------------------------------------- 1 | #include "main.h" 2 | #include "usart.h" 3 | 4 | int __io_putchar(int ch){ 5 | HAL_UART_Transmit(&huart1, (uint8_t*)&ch,1,HAL_MAX_DELAY); 6 | return ch; 7 | } 8 | 9 | int __io_getchar(void){ 10 | // uint8_t ch; 11 | // HAL_UART_Receive(&huart1, &ch, 1, HAL_MAX_DELAY); 12 | // return ch; 13 | } -------------------------------------------------------------------------------- /GUI/st7735/image.h: -------------------------------------------------------------------------------- 1 | #ifndef __IMAGE_H__ 2 | #define __IMAGE_H__ 3 | 4 | #include "st7735.h" 5 | 6 | #ifdef ST7735_IS_128X128 7 | 8 | extern const uint16_t test_img_128x128[][128]; 9 | #endif // ST7735_IS_128X128 10 | 11 | #ifdef ST7735_IS_160X80 12 | extern const uint16_t head_portrait_80x80[][80]; 13 | 14 | #endif 15 | 16 | #endif // __IMAGE_H__ -------------------------------------------------------------------------------- /GUI/st7735/fonts.h: -------------------------------------------------------------------------------- 1 | /* vim: set ai et ts=4 sw=4: */ 2 | #ifndef __FONTS_H__ 3 | #define __FONTS_H__ 4 | 5 | #include 6 | 7 | typedef struct { 8 | const uint8_t width; 9 | uint8_t height; 10 | const uint16_t *data; 11 | } FontDef; 12 | 13 | 14 | extern FontDef Font_7x10; 15 | extern FontDef Font_11x18; 16 | extern FontDef Font_16x26; 17 | 18 | #endif // __FONTS_H__ 19 | -------------------------------------------------------------------------------- /.idea/encodings.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /FOC/hardware_specific/stm32_mcu.h: -------------------------------------------------------------------------------- 1 | #ifndef FOC_DRIVER_STM32_MCU_H 2 | #define FOC_DRIVER_STM32_MCU_H 3 | 4 | #include "hardware_api.h" 5 | #include "tim.h" 6 | 7 | // default pwm parameters 8 | #define _PWM_RESOLUTION 12 // 12bit 9 | #define _PWM_RANGE 4095.0 // 2^12 -1 = 4095 10 | #define _PWM_FREQUENCY 25000 // 25khz 11 | #define _PWM_FREQUENCY_MAX 50000 // 50khz 12 | 13 | #define _STM32_TIMER_HANDLE &htim1 14 | 15 | #endif //FOC_DRIVER_STM32_MCU_H 16 | -------------------------------------------------------------------------------- /FOC/FOC_LPF.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Aiano on 2022/9/3. 3 | // 4 | 5 | #ifndef FOC_DRIVER_FOC_LPF_H 6 | #define FOC_DRIVER_FOC_LPF_H 7 | 8 | typedef struct { 9 | float alpha; 10 | float last_output; 11 | }LPF_Datatype; 12 | 13 | extern LPF_Datatype lpf_velocity; 14 | extern LPF_Datatype lpf_spring; 15 | extern LPF_Datatype lpf_cs[3]; 16 | extern LPF_Datatype lpf_current_d; 17 | extern LPF_Datatype lpf_current_q; 18 | 19 | void FOC_lpf_set_parameters(); 20 | float FOC_low_pass_filter(LPF_Datatype *lpf, float input); 21 | #endif //FOC_DRIVER_FOC_LPF_H 22 | -------------------------------------------------------------------------------- /FOC/hardware_api.h: -------------------------------------------------------------------------------- 1 | #ifndef FOC_DRIVER_HARDWARE_API_H 2 | #define FOC_DRIVER_HARDWARE_API_H 3 | 4 | #include "FOC_utils.h" 5 | 6 | #define STM32 7 | 8 | void _init3PWM(); 9 | 10 | /** 11 | * Function setting the duty cycle to the pwm pin (ex. analogWrite()) 12 | * - BLDC driver - 3PWM setting 13 | * - hardware specific 14 | * 15 | * @param dc_a duty cycle phase A [0, 1] 16 | * @param dc_b duty cycle phase B [0, 1] 17 | * @param dc_c duty cycle phase C [0, 1] 18 | */ 19 | void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c); 20 | 21 | #endif //FOC_DRIVER_HARDWARE_API_H 22 | -------------------------------------------------------------------------------- /FOC/FOC_conf.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file FOC_conf.h 3 | * @brief configurations of FOC algorithm 4 | */ 5 | 6 | #ifndef FOC_DRIVER_FOC_CONF_H 7 | #define FOC_DRIVER_FOC_CONF_H 8 | 9 | // Driver configuration 10 | #define VOLTAGE_LIMIT 8 11 | 12 | // BLDC motor configuration 13 | #define POLE_PAIR 7 14 | #define ZERO_ELECTRICAL_ANGLE 0.85f 15 | 16 | // Magnetic sensor configuration 17 | #define SENSOR_VALUE_RANGE 4095 18 | #define SENSOR_DIRECTION 1 19 | 20 | // Control mode, uncomment one at a time 21 | //#define FOC_MODE_VOLTAGE_CONTROL 22 | #define FOC_MODE_CURRENT_CONTROL 23 | 24 | #endif //FOC_DRIVER_FOC_CONF_H 25 | -------------------------------------------------------------------------------- /BSP/bsp_button.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Aiano on 2022/7/22. 3 | // 4 | 5 | #ifndef INC_2022_PROVINCE_A_BSP_BUTTON_H 6 | #define INC_2022_PROVINCE_A_BSP_BUTTON_H 7 | 8 | #include "main.h" 9 | 10 | #define BUTTON_Port GPIOB 11 | #define BUTTON_LEFT GPIO_PIN_10 12 | #define BUTTON_RIGHT GPIO_PIN_13 13 | #define BUTTON_CONFIRM GPIO_PIN_11 14 | #define BUTTON_CANCEL GPIO_PIN_12 15 | 16 | extern uint8_t button_press_pending_flag; 17 | 18 | extern uint8_t button_left_press_pending_flag; 19 | extern uint8_t button_right_press_pending_flag; 20 | extern uint8_t button_confirm_press_pending_flag; 21 | extern uint8_t button_cancel_press_pending_flag; 22 | 23 | void button_reset_all_flags(); 24 | 25 | #endif //INC_2022_PROVINCE_A_BSP_BUTTON_H 26 | -------------------------------------------------------------------------------- /FOC/FOC_PID.h: -------------------------------------------------------------------------------- 1 | #ifndef FOC_DRIVER_FOC_PID_H 2 | #define FOC_DRIVER_FOC_PID_H 3 | 4 | typedef struct { 5 | float Kp; 6 | float Ki; 7 | float Kd; 8 | 9 | float integral; 10 | float last_error; 11 | 12 | float max_integral; 13 | float min_integral; 14 | 15 | float max_u; 16 | float min_u; 17 | 18 | float dead_zone; 19 | } PID_Datatype; 20 | 21 | extern PID_Datatype pid_velocity; 22 | extern PID_Datatype pid_position; 23 | extern PID_Datatype pid_spring; 24 | extern PID_Datatype pid_spring_with_damp; 25 | extern PID_Datatype pid_damp; 26 | extern PID_Datatype pid_zero_resistance; 27 | extern PID_Datatype pid_knob; 28 | extern PID_Datatype pid_current_q; 29 | extern PID_Datatype pid_current_d; 30 | 31 | void pid_set_parameters(); 32 | float pid_get_u(PID_Datatype *pid, float target, float real); 33 | 34 | #endif //FOC_DRIVER_FOC_PID_H 35 | -------------------------------------------------------------------------------- /FOC/hardware_specific/stm32_mcu.c: -------------------------------------------------------------------------------- 1 | #include "stm32_mcu.h" 2 | #ifdef STM32 3 | 4 | #include "main.h" 5 | 6 | void _init3PWM(){ 7 | HAL_GPIO_WritePin(EN_GPIO_Port, EN_Pin, GPIO_PIN_SET); 8 | 9 | HAL_TIM_Base_Start_IT(&htim1); 10 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_1); 11 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2); 12 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3); 13 | } 14 | 15 | /** 16 | * @brief write duty cycle for 3 phase motor 17 | * @param dc_a [0,1] 18 | * @param dc_b [0,1] 19 | * @param dc_c [0,1] 20 | * @param params 21 | */ 22 | void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c) { 23 | // transform duty cycle from [0,1] to [0,_PWM_RANGE] 24 | __HAL_TIM_SET_COMPARE(_STM32_TIMER_HANDLE, TIM_CHANNEL_1, _PWM_RANGE*dc_a); 25 | __HAL_TIM_SET_COMPARE(_STM32_TIMER_HANDLE, TIM_CHANNEL_2, _PWM_RANGE*dc_b); 26 | __HAL_TIM_SET_COMPARE(_STM32_TIMER_HANDLE, TIM_CHANNEL_3, _PWM_RANGE*dc_c); 27 | } 28 | 29 | #endif -------------------------------------------------------------------------------- /FOC/FOC_LPF.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Aiano on 2022/9/3. 3 | // 4 | 5 | #include "FOC_LPF.h" 6 | 7 | LPF_Datatype lpf_velocity; 8 | LPF_Datatype lpf_spring; 9 | LPF_Datatype lpf_cs[3]; 10 | LPF_Datatype lpf_current_d; 11 | LPF_Datatype lpf_current_q; 12 | 13 | 14 | void FOC_lpf_set_parameters() { 15 | lpf_velocity.last_output = 0; 16 | lpf_velocity.alpha = 0.5; 17 | 18 | lpf_spring.last_output = 0; 19 | lpf_spring.alpha = 0.2; 20 | 21 | for (int i = 0; i < 3; ++i) { 22 | lpf_cs[i].last_output = 0; 23 | lpf_cs[i].alpha = 0.1; 24 | } 25 | 26 | lpf_current_d.last_output = 0; 27 | lpf_current_d.alpha = 0.2; 28 | 29 | lpf_current_q.last_output = 0; 30 | lpf_current_q.alpha = 0.2; 31 | } 32 | 33 | float FOC_low_pass_filter(LPF_Datatype *lpf, float input) { 34 | float output = lpf->alpha * input + (1 - lpf->alpha) * lpf->last_output; 35 | lpf->last_output = output; 36 | 37 | return output; 38 | } 39 | -------------------------------------------------------------------------------- /FOC/FOC.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file FOC.h 3 | * @author Aiano_czm 4 | * @brief 5 | */ 6 | 7 | #ifndef FOC_DRIVER_FOC_H 8 | #define FOC_DRIVER_FOC_H 9 | 10 | #include "FOC_PID.h" 11 | 12 | typedef enum{ 13 | OPEN_LOOP_POSITION_CONTROL = 0, 14 | OPEN_LOOP_SPEED_CONTROL, 15 | TORQUE_CONTROL, 16 | SPEED_CONTROL, 17 | POSITION_CONTROL, 18 | SPRING, 19 | SPRING_WITH_DAMP, 20 | DAMP, 21 | KNOB, 22 | ZERO_RESISTANCE 23 | } FOC_CONTROL_MODE; 24 | 25 | #define FOC_CONTROL_MODE_NUM 10 26 | 27 | void FOC_init(); 28 | void FOC_electrical_angle_calibration(); 29 | void FOC_SVPWM(float Uq, float Ud, float angle); 30 | void FOC_Clarke_Park(float Ia, float Ib, float Ic, float angle, float *Id, float *Iq); 31 | float FOC_get_mechanical_angle(); 32 | float FOC_electrical_angle(); 33 | float FOC_get_velocity(); 34 | 35 | // Some modes to choose 36 | void FOC_open_loop_voltage_control_loop(float Uq); 37 | void FOC_current_control_loop(float target_Iq); 38 | void FOC_velocity_control_loop(float target_velocity); 39 | void FOC_position_control_loop(float target_angle); 40 | void FOC_spring_loop(float target_angle, PID_Datatype *pid); 41 | void FOC_knob_loop(uint8_t sector_num); 42 | #endif //FOC_DRIVER_FOC_H 43 | -------------------------------------------------------------------------------- /.project: -------------------------------------------------------------------------------- 1 | 2 | 3 | FOC_Driver 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 | org.eclipse.cdt.core.cnature 24 | com.st.stm32cube.ide.mcu.MCUCubeIdeServicesRevAev2ProjectNature 25 | com.st.stm32cube.ide.mcu.MCUCubeProjectNature 26 | com.st.stm32cube.ide.mcu.MCUAdvancedStructureProjectNature 27 | com.st.stm32cube.ide.mcu.MCUSingleCpuProjectNature 28 | com.st.stm32cube.ide.mcu.MCURootProjectNature 29 | org.eclipse.cdt.managedbuilder.core.managedBuildNature 30 | org.eclipse.cdt.managedbuilder.core.ScannerConfigNature 31 | 32 | 33 | -------------------------------------------------------------------------------- /BSP/bsp_button.c: -------------------------------------------------------------------------------- 1 | // 2 | // Created by Aiano on 2022/7/22. 3 | // 4 | 5 | #include "bsp_button.h" 6 | 7 | uint8_t button_press_pending_flag = 0; 8 | uint8_t button_left_press_pending_flag = 0; 9 | uint8_t button_right_press_pending_flag = 0; 10 | uint8_t button_confirm_press_pending_flag = 0; 11 | uint8_t button_cancel_press_pending_flag = 0; 12 | 13 | void button_reset_all_flags() { 14 | button_press_pending_flag = 0; 15 | 16 | button_left_press_pending_flag = 0; 17 | button_right_press_pending_flag = 0; 18 | button_confirm_press_pending_flag = 0; 19 | button_cancel_press_pending_flag = 0; 20 | } 21 | 22 | void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin) { 23 | button_press_pending_flag = 1; 24 | 25 | if (HAL_GPIO_ReadPin(BUTTON_Port, GPIO_Pin) == 0) { 26 | switch (GPIO_Pin) { 27 | case BUTTON_LEFT: 28 | button_left_press_pending_flag = 1; 29 | break; 30 | case BUTTON_RIGHT: 31 | button_right_press_pending_flag = 1; 32 | break; 33 | case BUTTON_CONFIRM: 34 | button_confirm_press_pending_flag = 1; 35 | break; 36 | case BUTTON_CANCEL: 37 | button_cancel_press_pending_flag = 1; 38 | break; 39 | } 40 | } 41 | } -------------------------------------------------------------------------------- /Core/Inc/gpio.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file gpio.h 5 | * @brief This file contains all the function prototypes for 6 | * the gpio.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __GPIO_H__ 22 | #define __GPIO_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | /* USER CODE BEGIN Private defines */ 36 | 37 | /* USER CODE END Private defines */ 38 | 39 | void MX_GPIO_Init(void); 40 | 41 | /* USER CODE BEGIN Prototypes */ 42 | 43 | /* USER CODE END Prototypes */ 44 | 45 | #ifdef __cplusplus 46 | } 47 | #endif 48 | #endif /*__ GPIO_H__ */ 49 | 50 | -------------------------------------------------------------------------------- /Core/Inc/adc.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file adc.h 5 | * @brief This file contains all the function prototypes for 6 | * the adc.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __ADC_H__ 22 | #define __ADC_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern ADC_HandleTypeDef hadc1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_ADC1_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __ADC_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /Core/Inc/can.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file can.h 5 | * @brief This file contains all the function prototypes for 6 | * the can.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __CAN_H__ 22 | #define __CAN_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern CAN_HandleTypeDef hcan; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_CAN_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __CAN_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /Core/Inc/i2c.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file i2c.h 5 | * @brief This file contains all the function prototypes for 6 | * the i2c.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __I2C_H__ 22 | #define __I2C_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern I2C_HandleTypeDef hi2c1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_I2C1_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __I2C_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /Core/Inc/spi.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file spi.h 5 | * @brief This file contains all the function prototypes for 6 | * the spi.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __SPI_H__ 22 | #define __SPI_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern SPI_HandleTypeDef hspi1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_SPI1_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __SPI_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /FOC/sensor/current_sense.c: -------------------------------------------------------------------------------- 1 | #include "current_sense.h" 2 | #include "adc.h" 3 | #include "FOC.h" 4 | #include "math.h" 5 | #include "FOC_utils.h" 6 | #include "FOC_LPF.h" 7 | 8 | float cs_value[3]; 9 | float cs_zero_value = 2081; 10 | 11 | void cs_init() { 12 | HAL_ADCEx_Calibration_Start(&hadc1); 13 | } 14 | 15 | // 转换函数 16 | // 多通道扫描模式 17 | // 18 | uint8_t cs_get_value() { 19 | for (int i = 0; i < 3; ++i) { 20 | // Enables ADC, starts conversion of regular group. 21 | HAL_ADC_Start(&hadc1); 22 | // Wait for regular group conversion to be completed. 23 | HAL_ADC_PollForConversion(&hadc1, 100); 24 | // 判断ADC是否转换成功 25 | // if (HAL_IS_BIT_SET(HAL_ADC_GetState(&hadc1), HAL_ADC_STATE_REG_EOC)) { 26 | 27 | // Get ADC regular group conversion result. 28 | // Reading register DR automatically clears ADC flag EOC (ADC group regular end of unitary conversion). 29 | // 该函数读取寄存器DR同时自动清除了EOC(End Of unitary Conversation)标志位 30 | 31 | // cs_value[i] = HAL_ADC_GetValue(&hadc1) - cs_zero_value; 32 | cs_value[i] = FOC_low_pass_filter(lpf_cs + i, HAL_ADC_GetValue(&hadc1) - cs_zero_value); 33 | // } else { 34 | // HAL_ADC_Stop(&hadc1); 35 | // 如果转换失败就返回-1 36 | // return -1; 37 | // } 38 | } 39 | // Stop ADC conversion of regular group, disable ADC peripheral. 40 | HAL_ADC_Stop(&hadc1); 41 | 42 | // cs_value[0] = -cs_value[1] - cs_value[2] + 3 * cs_zero_value; 43 | return 0; 44 | } 45 | 46 | 47 | 48 | 49 | -------------------------------------------------------------------------------- /Core/Inc/usart.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file usart.h 5 | * @brief This file contains all the function prototypes for 6 | * the usart.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USART_H__ 22 | #define __USART_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern UART_HandleTypeDef huart1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_USART1_UART_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __USART_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /Core/Inc/tim.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file tim.h 5 | * @brief This file contains all the function prototypes for 6 | * the tim.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __TIM_H__ 22 | #define __TIM_H__ 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "main.h" 30 | 31 | /* USER CODE BEGIN Includes */ 32 | 33 | /* USER CODE END Includes */ 34 | 35 | extern TIM_HandleTypeDef htim1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_TIM1_Init(void); 42 | 43 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); 44 | 45 | /* USER CODE BEGIN Prototypes */ 46 | 47 | /* USER CODE END Prototypes */ 48 | 49 | #ifdef __cplusplus 50 | } 51 | #endif 52 | 53 | #endif /* __TIM_H__ */ 54 | 55 | -------------------------------------------------------------------------------- /Drivers/STM32F1xx_HAL_Driver/License.md: -------------------------------------------------------------------------------- 1 | Copyright 2016(-2021) STMicroelectronics. 2 | All rights reserved. 3 | 4 | Redistribution and use in source and binary forms, with or without modification, 5 | are permitted provided that the following conditions are met: 6 | 7 | 1. Redistributions of source code must retain the above copyright notice, this 8 | list of conditions and the following disclaimer. 9 | 10 | 2. Redistributions in binary form must reproduce the above copyright notice, 11 | this list of conditions and the following disclaimer in the documentation and/or 12 | other materials provided with the distribution. 13 | 14 | 3. Neither the name of the copyright holder nor the names of its contributors 15 | may be used to endorse or promote products derived from this software without 16 | specific prior written permission. 17 | 18 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 19 | ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 20 | WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 21 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR 22 | ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 23 | (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 24 | LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON 25 | ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 26 | (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 27 | SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 28 | -------------------------------------------------------------------------------- /GUI/gui.h: -------------------------------------------------------------------------------- 1 | #ifndef FOC_DRIVER_GUI_H 2 | #define FOC_DRIVER_GUI_H 3 | #include "main.h" 4 | #include "FOC.h" 5 | #include "st7735.h" 6 | 7 | //#define LIGHT_MODE 8 | #define DARK_MODE 9 | 10 | #ifdef LIGHT_MODE 11 | #define BACKGROUND_COLOR ST7735_WHITE 12 | #define TEXT_COLOR ST7735_BLACK 13 | #define TITLE_COLOR ST7735_BLUE 14 | #define SELECTED_COLOR ST7735_BLUE 15 | #define BAR_COLOR ST7735_RED 16 | #endif 17 | 18 | #ifdef DARK_MODE 19 | #define BACKGROUND_COLOR ST7735_BLACK 20 | #define TEXT_COLOR ST7735_WHITE 21 | #define TITLE_COLOR ST7735_YELLOW 22 | #define SELECTED_COLOR ST7735_BLUE 23 | #define BAR_COLOR ST7735_RED 24 | #endif 25 | 26 | extern const char foc_mode_name[FOC_CONTROL_MODE_NUM][20]; 27 | 28 | void gui_draw_line(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color); 29 | void gui_draw_rectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint8_t fill, uint16_t color); 30 | void gui_draw_triangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color); 31 | void gui_draw_init(const char *init_info, uint8_t refresh); 32 | void gui_draw_mode_selection(FOC_CONTROL_MODE mode); 33 | void gui_draw_position_mode(float angle, uint8_t refresh); 34 | void gui_draw_knob_mode(uint8_t sector_num, uint8_t k, uint8_t max_force, uint8_t select_param, uint8_t change, 35 | uint8_t refresh); 36 | void 37 | gui_draw_button(uint16_t x, uint16_t y, uint16_t w, uint16_t h, const char *string, uint16_t color, uint16_t bgcolor); 38 | void gui_draw_parameter(uint16_t x, uint16_t y, const char *item, int16_t value, uint8_t change, uint8_t selected); 39 | void gui_draw_test(); 40 | 41 | #endif //FOC_DRIVER_GUI_H 42 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /Core/Inc/stm32f1xx_it.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32f1xx_it.h 5 | * @brief This file contains the headers of the interrupt handlers. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2022 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file 13 | * in the root directory of this software component. 14 | * If no LICENSE file comes with this software, it is provided AS-IS. 15 | * 16 | ****************************************************************************** 17 | */ 18 | /* USER CODE END Header */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __STM32F1xx_IT_H 22 | #define __STM32F1xx_IT_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Private includes ----------------------------------------------------------*/ 29 | /* USER CODE BEGIN Includes */ 30 | 31 | /* USER CODE END Includes */ 32 | 33 | /* Exported types ------------------------------------------------------------*/ 34 | /* USER CODE BEGIN ET */ 35 | 36 | /* USER CODE END ET */ 37 | 38 | /* Exported constants --------------------------------------------------------*/ 39 | /* USER CODE BEGIN EC */ 40 | 41 | /* USER CODE END EC */ 42 | 43 | /* Exported macro ------------------------------------------------------------*/ 44 | /* USER CODE BEGIN EM */ 45 | 46 | /* USER CODE END EM */ 47 | 48 | /* Exported functions prototypes ---------------------------------------------*/ 49 | void NMI_Handler(void); 50 | void HardFault_Handler(void); 51 | void MemManage_Handler(void); 52 | void BusFault_Handler(void); 53 | void UsageFault_Handler(void); 54 | void DebugMon_Handler(void); 55 | void TIM4_IRQHandler(void); 56 | void EXTI15_10_IRQHandler(void); 57 | /* USER CODE BEGIN EFP */ 58 | 59 | /* USER CODE END EFP */ 60 | 61 | #ifdef __cplusplus 62 | } 63 | #endif 64 | 65 | #endif /* __STM32F1xx_IT_H */ 66 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32F1xx/Include/system_stm32f1xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32f10x.h 4 | * @author MCD Application Team 5 | * @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File. 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 | /** @addtogroup CMSIS 21 | * @{ 22 | */ 23 | 24 | /** @addtogroup stm32f10x_system 25 | * @{ 26 | */ 27 | 28 | /** 29 | * @brief Define to prevent recursive inclusion 30 | */ 31 | #ifndef __SYSTEM_STM32F10X_H 32 | #define __SYSTEM_STM32F10X_H 33 | 34 | #ifdef __cplusplus 35 | extern "C" { 36 | #endif 37 | 38 | /** @addtogroup STM32F10x_System_Includes 39 | * @{ 40 | */ 41 | 42 | /** 43 | * @} 44 | */ 45 | 46 | 47 | /** @addtogroup STM32F10x_System_Exported_types 48 | * @{ 49 | */ 50 | 51 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ 52 | extern const uint8_t AHBPrescTable[16U]; /*!< AHB prescalers table values */ 53 | extern const uint8_t APBPrescTable[8U]; /*!< APB prescalers table values */ 54 | 55 | /** 56 | * @} 57 | */ 58 | 59 | /** @addtogroup STM32F10x_System_Exported_Constants 60 | * @{ 61 | */ 62 | 63 | /** 64 | * @} 65 | */ 66 | 67 | /** @addtogroup STM32F10x_System_Exported_Macros 68 | * @{ 69 | */ 70 | 71 | /** 72 | * @} 73 | */ 74 | 75 | /** @addtogroup STM32F10x_System_Exported_Functions 76 | * @{ 77 | */ 78 | 79 | extern void SystemInit(void); 80 | extern void SystemCoreClockUpdate(void); 81 | /** 82 | * @} 83 | */ 84 | 85 | #ifdef __cplusplus 86 | } 87 | #endif 88 | 89 | #endif /*__SYSTEM_STM32F10X_H */ 90 | 91 | /** 92 | * @} 93 | */ 94 | 95 | /** 96 | * @} 97 | */ 98 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 99 | -------------------------------------------------------------------------------- /FOC/FOC_utils.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file FOC_utils.h 3 | * @brief some useful functions for FOC algorithm 4 | */ 5 | 6 | #ifndef FOC_DRIVER_FOC_UTILS_H 7 | #define FOC_DRIVER_FOC_UTILS_H 8 | 9 | // sign function 10 | #define _sign(a) ( ( (a) < 0 ) ? -1 : ( (a) > 0 ) ) 11 | #define _round(x) ((x)>=0?(long)((x)+0.5f):(long)((x)-0.5f)) 12 | #define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt))) 13 | #define _sqrt(a) (_sqrtApprox(a)) 14 | #define _isset(a) ( (a) != (NOT_SET) ) 15 | #define _UNUSED(v) (void) (v) 16 | 17 | // utility defines 18 | #define _2_SQRT3 1.15470053838f 19 | #define _SQRT3 1.73205080757f 20 | #define _1_SQRT3 0.57735026919f 21 | #define _SQRT3_2 0.86602540378f 22 | #define _SQRT2 1.41421356237f 23 | #define _120_D2R 2.09439510239f 24 | #define _PI 3.14159265359f 25 | #define _PI_2 1.57079632679f 26 | #define _PI_3 1.0471975512f 27 | #define _2PI 6.28318530718f 28 | #define _3PI_2 4.71238898038f 29 | #define _PI_6 0.52359877559f 30 | #define _RPM_TO_RADS 0.10471975512f 31 | #define _RADIAN_TO_DEGREE 57.295779513f 32 | 33 | #define NOT_SET -12345.0 34 | #define _HIGH_IMPEDANCE 0 35 | #define _HIGH_Z _HIGH_IMPEDANCE 36 | #define _ACTIVE 1 37 | #define _NC (NOT_SET) 38 | 39 | // dq current structure 40 | struct DQCurrent_s 41 | { 42 | float d; 43 | float q; 44 | }; 45 | // phase current structure 46 | struct PhaseCurrent_s 47 | { 48 | float a; 49 | float b; 50 | float c; 51 | }; 52 | // dq voltage structs 53 | struct DQVoltage_s 54 | { 55 | float d; 56 | float q; 57 | }; 58 | 59 | 60 | /** 61 | * Function approximating the sine calculation by using fixed size array 62 | * - execution time ~40us (Arduino UNO) 63 | * 64 | * @param a angle in between 0 and 2PI 65 | */ 66 | float _sin(float a); 67 | /** 68 | * Function approximating cosine calculation by using fixed size array 69 | * - execution time ~50us (Arduino UNO) 70 | * 71 | * @param a angle in between 0 and 2PI 72 | */ 73 | float _cos(float a); 74 | 75 | /** 76 | * normalizing radian angle to [0,2PI] 77 | * @param angle - angle to be normalized 78 | */ 79 | float _normalizeAngle(float angle); 80 | 81 | 82 | /** 83 | * Electrical angle calculation 84 | * 85 | * @param shaft_angle - shaft angle of the motor 86 | * @param pole_pairs - number of pole pairs 87 | */ 88 | float _electricalAngle(float shaft_angle, int pole_pairs); 89 | 90 | /** 91 | * Function approximating square root function 92 | * - using fast inverse square root 93 | * 94 | * @param value - number 95 | */ 96 | float _sqrtApprox(float value); 97 | 98 | #endif //FOC_DRIVER_FOC_UTILS_H 99 | -------------------------------------------------------------------------------- /Core/Src/stm32f1xx_hal_msp.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32f1xx_hal_msp.c 5 | * @brief This file provides code for the MSP Initialization 6 | * and de-Initialization codes. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "main.h" 23 | /* USER CODE BEGIN Includes */ 24 | 25 | /* USER CODE END Includes */ 26 | 27 | /* Private typedef -----------------------------------------------------------*/ 28 | /* USER CODE BEGIN TD */ 29 | 30 | /* USER CODE END TD */ 31 | 32 | /* Private define ------------------------------------------------------------*/ 33 | /* USER CODE BEGIN Define */ 34 | 35 | /* USER CODE END Define */ 36 | 37 | /* Private macro -------------------------------------------------------------*/ 38 | /* USER CODE BEGIN Macro */ 39 | 40 | /* USER CODE END Macro */ 41 | 42 | /* Private variables ---------------------------------------------------------*/ 43 | /* USER CODE BEGIN PV */ 44 | 45 | /* USER CODE END PV */ 46 | 47 | /* Private function prototypes -----------------------------------------------*/ 48 | /* USER CODE BEGIN PFP */ 49 | 50 | /* USER CODE END PFP */ 51 | 52 | /* External functions --------------------------------------------------------*/ 53 | /* USER CODE BEGIN ExternalFunctions */ 54 | 55 | /* USER CODE END ExternalFunctions */ 56 | 57 | /* USER CODE BEGIN 0 */ 58 | 59 | /* USER CODE END 0 */ 60 | /** 61 | * Initializes the Global MSP. 62 | */ 63 | void HAL_MspInit(void) 64 | { 65 | /* USER CODE BEGIN MspInit 0 */ 66 | 67 | /* USER CODE END MspInit 0 */ 68 | 69 | __HAL_RCC_AFIO_CLK_ENABLE(); 70 | __HAL_RCC_PWR_CLK_ENABLE(); 71 | 72 | /* System interrupt init*/ 73 | /* PendSV_IRQn interrupt configuration */ 74 | HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); 75 | 76 | /** NOJTAG: JTAG-DP Disabled and SW-DP Enabled 77 | */ 78 | __HAL_AFIO_REMAP_SWJ_NOJTAG(); 79 | 80 | /* USER CODE BEGIN MspInit 1 */ 81 | 82 | /* USER CODE END MspInit 1 */ 83 | } 84 | 85 | /* USER CODE BEGIN 1 */ 86 | 87 | /* USER CODE END 1 */ 88 | -------------------------------------------------------------------------------- /Core/Src/gpio.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file gpio.c 5 | * @brief This file provides code for the configuration 6 | * of all used GPIO pins. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Includes ------------------------------------------------------------------*/ 22 | #include "gpio.h" 23 | 24 | /* USER CODE BEGIN 0 */ 25 | 26 | /* USER CODE END 0 */ 27 | 28 | /*----------------------------------------------------------------------------*/ 29 | /* Configure GPIO */ 30 | /*----------------------------------------------------------------------------*/ 31 | /* USER CODE BEGIN 1 */ 32 | 33 | /* USER CODE END 1 */ 34 | 35 | /** Configure pins as 36 | * Analog 37 | * Input 38 | * Output 39 | * EVENT_OUT 40 | * EXTI 41 | */ 42 | void MX_GPIO_Init(void) 43 | { 44 | 45 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 46 | 47 | /* GPIO Ports Clock Enable */ 48 | __HAL_RCC_GPIOD_CLK_ENABLE(); 49 | __HAL_RCC_GPIOA_CLK_ENABLE(); 50 | __HAL_RCC_GPIOB_CLK_ENABLE(); 51 | 52 | /*Configure GPIO pin Output Level */ 53 | HAL_GPIO_WritePin(GPIOA, LED_Pin|LCD_DC_Pin|LCD_RST_Pin, GPIO_PIN_RESET); 54 | 55 | /*Configure GPIO pin Output Level */ 56 | HAL_GPIO_WritePin(EN_GPIO_Port, EN_Pin, GPIO_PIN_RESET); 57 | 58 | /*Configure GPIO pins : PAPin PAPin PAPin */ 59 | GPIO_InitStruct.Pin = LED_Pin|LCD_DC_Pin|LCD_RST_Pin; 60 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 61 | GPIO_InitStruct.Pull = GPIO_NOPULL; 62 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 63 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 64 | 65 | /*Configure GPIO pins : PBPin PBPin PBPin PBPin */ 66 | GPIO_InitStruct.Pin = KEY1_Pin|KEY2_Pin|KEY3_Pin|KEY4_Pin; 67 | GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING; 68 | GPIO_InitStruct.Pull = GPIO_NOPULL; 69 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 70 | 71 | /*Configure GPIO pin : PtPin */ 72 | GPIO_InitStruct.Pin = EN_Pin; 73 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 74 | GPIO_InitStruct.Pull = GPIO_NOPULL; 75 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 76 | HAL_GPIO_Init(EN_GPIO_Port, &GPIO_InitStruct); 77 | 78 | /* EXTI interrupt init*/ 79 | HAL_NVIC_SetPriority(EXTI15_10_IRQn, 5, 0); 80 | HAL_NVIC_EnableIRQ(EXTI15_10_IRQn); 81 | 82 | } 83 | 84 | /* USER CODE BEGIN 2 */ 85 | 86 | /* USER CODE END 2 */ 87 | -------------------------------------------------------------------------------- /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 | -------------------------------------------------------------------------------- /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) 2022 STMicroelectronics. 14 | * All rights reserved. 15 | * 16 | * This software is licensed under terms that can be found in the LICENSE file 17 | * in the root directory of this software component. 18 | * If no LICENSE file comes with this software, it is provided AS-IS. 19 | * 20 | ****************************************************************************** 21 | */ 22 | 23 | /* Includes */ 24 | #include 25 | #include 26 | 27 | /** 28 | * Pointer to the current high watermark of the heap usage 29 | */ 30 | static uint8_t *__sbrk_heap_end = NULL; 31 | 32 | /** 33 | * @brief _sbrk() allocates memory to the newlib heap and is used by malloc 34 | * and others from the C library 35 | * 36 | * @verbatim 37 | * ############################################################################ 38 | * # .data # .bss # newlib heap # MSP stack # 39 | * # # # # Reserved by _Min_Stack_Size # 40 | * ############################################################################ 41 | * ^-- RAM start ^-- _end _estack, RAM end --^ 42 | * @endverbatim 43 | * 44 | * This implementation starts allocating at the '_end' linker symbol 45 | * The '_Min_Stack_Size' linker symbol reserves a memory for the MSP stack 46 | * The implementation considers '_estack' linker symbol to be RAM end 47 | * NOTE: If the MSP stack, at any point during execution, grows larger than the 48 | * reserved size, please increase the '_Min_Stack_Size'. 49 | * 50 | * @param incr Memory size 51 | * @return Pointer to allocated memory 52 | */ 53 | void *_sbrk(ptrdiff_t incr) 54 | { 55 | extern uint8_t _end; /* Symbol defined in the linker script */ 56 | extern uint8_t _estack; /* Symbol defined in the linker script */ 57 | extern uint32_t _Min_Stack_Size; /* Symbol defined in the linker script */ 58 | const uint32_t stack_limit = (uint32_t)&_estack - (uint32_t)&_Min_Stack_Size; 59 | const uint8_t *max_heap = (uint8_t *)stack_limit; 60 | uint8_t *prev_heap_end; 61 | 62 | /* Initialize heap end at first call */ 63 | if (NULL == __sbrk_heap_end) 64 | { 65 | __sbrk_heap_end = &_end; 66 | } 67 | 68 | /* Protect heap from growing into the reserved MSP stack */ 69 | if (__sbrk_heap_end + incr > max_heap) 70 | { 71 | errno = ENOMEM; 72 | return (void *)-1; 73 | } 74 | 75 | prev_heap_end = __sbrk_heap_end; 76 | __sbrk_heap_end += incr; 77 | 78 | return (void *)prev_heap_end; 79 | } 80 | -------------------------------------------------------------------------------- /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) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | 21 | /* Define to prevent recursive inclusion -------------------------------------*/ 22 | #ifndef __MAIN_H 23 | #define __MAIN_H 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include "stm32f1xx_hal.h" 31 | 32 | /* Private includes ----------------------------------------------------------*/ 33 | /* USER CODE BEGIN Includes */ 34 | 35 | /* USER CODE END Includes */ 36 | 37 | /* Exported types ------------------------------------------------------------*/ 38 | /* USER CODE BEGIN ET */ 39 | 40 | /* USER CODE END ET */ 41 | 42 | /* Exported constants --------------------------------------------------------*/ 43 | /* USER CODE BEGIN EC */ 44 | 45 | /* USER CODE END EC */ 46 | 47 | /* Exported macro ------------------------------------------------------------*/ 48 | /* USER CODE BEGIN EM */ 49 | 50 | /* USER CODE END EM */ 51 | 52 | /* Exported functions prototypes ---------------------------------------------*/ 53 | void Error_Handler(void); 54 | 55 | /* USER CODE BEGIN EFP */ 56 | 57 | /* USER CODE END EFP */ 58 | 59 | /* Private defines -----------------------------------------------------------*/ 60 | #define CS1_Pin GPIO_PIN_0 61 | #define CS1_GPIO_Port GPIOA 62 | #define CS2_Pin GPIO_PIN_1 63 | #define CS2_GPIO_Port GPIOA 64 | #define CS3_Pin GPIO_PIN_2 65 | #define CS3_GPIO_Port GPIOA 66 | #define LED_Pin GPIO_PIN_3 67 | #define LED_GPIO_Port GPIOA 68 | #define LCD_DC_Pin GPIO_PIN_4 69 | #define LCD_DC_GPIO_Port GPIOA 70 | #define LCD_RST_Pin GPIO_PIN_6 71 | #define LCD_RST_GPIO_Port GPIOA 72 | #define KEY1_Pin GPIO_PIN_10 73 | #define KEY1_GPIO_Port GPIOB 74 | #define KEY1_EXTI_IRQn EXTI15_10_IRQn 75 | #define KEY2_Pin GPIO_PIN_11 76 | #define KEY2_GPIO_Port GPIOB 77 | #define KEY2_EXTI_IRQn EXTI15_10_IRQn 78 | #define KEY3_Pin GPIO_PIN_12 79 | #define KEY3_GPIO_Port GPIOB 80 | #define KEY3_EXTI_IRQn EXTI15_10_IRQn 81 | #define KEY4_Pin GPIO_PIN_13 82 | #define KEY4_GPIO_Port GPIOB 83 | #define KEY4_EXTI_IRQn EXTI15_10_IRQn 84 | #define EN_Pin GPIO_PIN_15 85 | #define EN_GPIO_Port GPIOB 86 | /* USER CODE BEGIN Private defines */ 87 | 88 | /* USER CODE END Private defines */ 89 | 90 | #ifdef __cplusplus 91 | } 92 | #endif 93 | 94 | #endif /* __MAIN_H */ 95 | -------------------------------------------------------------------------------- /CMakeLists_template.txt: -------------------------------------------------------------------------------- 1 | #${templateWarning} 2 | set(CMAKE_SYSTEM_NAME Generic) 3 | set(CMAKE_SYSTEM_VERSION 1) 4 | ${cmakeRequiredVersion} 5 | # specify cross compilers and tools 6 | set(CMAKE_C_COMPILER arm-none-eabi-gcc) 7 | set(CMAKE_CXX_COMPILER arm-none-eabi-g++) 8 | set(CMAKE_ASM_COMPILER arm-none-eabi-gcc) 9 | set(CMAKE_AR arm-none-eabi-ar) 10 | set(CMAKE_OBJCOPY arm-none-eabi-objcopy) 11 | set(CMAKE_OBJDUMP arm-none-eabi-objdump) 12 | set(SIZE arm-none-eabi-size) 13 | set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) 14 | 15 | # project settings 16 | project(${projectName} C CXX ASM) 17 | set(CMAKE_CXX_STANDARD 17) 18 | set(CMAKE_C_STANDARD 11) 19 | 20 | #Uncomment for hardware floating point 21 | #add_compile_definitions(ARM_MATH_CM4;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING) 22 | #add_compile_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16) 23 | #add_link_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16) 24 | 25 | #Uncomment for software floating point 26 | #add_compile_options(-mfloat-abi=soft) 27 | 28 | add_compile_options(-mcpu=${mcpu} -mthumb -mthumb-interwork) 29 | add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0) 30 | 31 | # uncomment to mitigate c++17 absolute addresses warnings 32 | #set(CMAKE_CXX_FLAGS "$${CMAKE_CXX_FLAGS} -Wno-register") 33 | 34 | # Enable assembler files preprocessing 35 | add_compile_options($<$:-x$assembler-with-cpp>) 36 | 37 | if ("$${CMAKE_BUILD_TYPE}" STREQUAL "Release") 38 | message(STATUS "Maximum optimization for speed") 39 | add_compile_options(-Ofast) 40 | elseif ("$${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo") 41 | message(STATUS "Maximum optimization for speed, debug info included") 42 | add_compile_options(-Ofast -g) 43 | elseif ("$${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel") 44 | message(STATUS "Maximum optimization for size") 45 | add_compile_options(-Os) 46 | else () 47 | message(STATUS "Minimal optimization, debug info included") 48 | add_compile_options(-Og -g) 49 | endif () 50 | 51 | include_directories(${includes} 52 | FOC 53 | FOC/hardware_specific 54 | FOC/sensor 55 | GUI 56 | GUI/st7735 57 | BSP) 58 | 59 | add_definitions(${defines}) 60 | 61 | file(GLOB_RECURSE SOURCES ${sources} 62 | "FOC/*.*" 63 | "GUI/*.*" 64 | "BSP/*.*") 65 | 66 | set(LINKER_SCRIPT $${CMAKE_SOURCE_DIR}/${linkerScript}) 67 | 68 | add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=$${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.map) 69 | add_link_options(-mcpu=${mcpu} -mthumb -mthumb-interwork) 70 | add_link_options(-T $${LINKER_SCRIPT}) 71 | 72 | add_executable($${PROJECT_NAME}.elf $${SOURCES} $${LINKER_SCRIPT}) 73 | 74 | set(HEX_FILE $${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.hex) 75 | set(BIN_FILE $${PROJECT_BINARY_DIR}/$${PROJECT_NAME}.bin) 76 | 77 | add_custom_command(TARGET $${PROJECT_NAME}.elf POST_BUILD 78 | COMMAND $${CMAKE_OBJCOPY} -Oihex $ $${HEX_FILE} 79 | COMMAND $${CMAKE_OBJCOPY} -Obinary $ $${BIN_FILE} 80 | COMMENT "Building $${HEX_FILE} 81 | Building $${BIN_FILE}") 82 | -------------------------------------------------------------------------------- /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) 2022 STMicroelectronics. 14 | * All rights reserved. 15 | * 16 | * This software is licensed under terms that can be found in the LICENSE file 17 | * in the root directory of this software component. 18 | * If no LICENSE file comes with this software, it is provided AS-IS. 19 | * 20 | ****************************************************************************** 21 | */ 22 | 23 | /* Includes */ 24 | #include 25 | #include 26 | #include 27 | #include 28 | #include 29 | #include 30 | #include 31 | #include 32 | 33 | 34 | /* Variables */ 35 | extern int __io_putchar(int ch) __attribute__((weak)); 36 | extern int __io_getchar(void) __attribute__((weak)); 37 | 38 | 39 | char *__env[1] = { 0 }; 40 | char **environ = __env; 41 | 42 | 43 | /* Functions */ 44 | void initialise_monitor_handles() 45 | { 46 | } 47 | 48 | int _getpid(void) 49 | { 50 | return 1; 51 | } 52 | 53 | int _kill(int pid, int sig) 54 | { 55 | errno = EINVAL; 56 | return -1; 57 | } 58 | 59 | void _exit (int status) 60 | { 61 | _kill(status, -1); 62 | while (1) {} /* Make sure we hang here */ 63 | } 64 | 65 | __attribute__((weak)) int _read(int file, char *ptr, int len) 66 | { 67 | int DataIdx; 68 | 69 | for (DataIdx = 0; DataIdx < len; DataIdx++) 70 | { 71 | *ptr++ = __io_getchar(); 72 | } 73 | 74 | return len; 75 | } 76 | 77 | __attribute__((weak)) int _write(int file, char *ptr, int len) 78 | { 79 | int DataIdx; 80 | 81 | for (DataIdx = 0; DataIdx < len; DataIdx++) 82 | { 83 | __io_putchar(*ptr++); 84 | } 85 | return len; 86 | } 87 | 88 | int _close(int file) 89 | { 90 | return -1; 91 | } 92 | 93 | 94 | int _fstat(int file, struct stat *st) 95 | { 96 | st->st_mode = S_IFCHR; 97 | return 0; 98 | } 99 | 100 | int _isatty(int file) 101 | { 102 | return 1; 103 | } 104 | 105 | int _lseek(int file, int ptr, int dir) 106 | { 107 | return 0; 108 | } 109 | 110 | int _open(char *path, int flags, ...) 111 | { 112 | /* Pretend like we always fail */ 113 | return -1; 114 | } 115 | 116 | int _wait(int *status) 117 | { 118 | errno = ECHILD; 119 | return -1; 120 | } 121 | 122 | int _unlink(char *name) 123 | { 124 | errno = ENOENT; 125 | return -1; 126 | } 127 | 128 | int _times(struct tms *buf) 129 | { 130 | return -1; 131 | } 132 | 133 | int _stat(char *file, struct stat *st) 134 | { 135 | st->st_mode = S_IFCHR; 136 | return 0; 137 | } 138 | 139 | int _link(char *old, char *new) 140 | { 141 | errno = EMLINK; 142 | return -1; 143 | } 144 | 145 | int _fork(void) 146 | { 147 | errno = EAGAIN; 148 | return -1; 149 | } 150 | 151 | int _execve(char *name, char **argv, char **env) 152 | { 153 | errno = ENOMEM; 154 | return -1; 155 | } 156 | -------------------------------------------------------------------------------- /Core/Src/i2c.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file i2c.c 5 | * @brief This file provides code for the configuration 6 | * of the I2C instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "i2c.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | I2C_HandleTypeDef hi2c1; 28 | 29 | /* I2C1 init function */ 30 | void MX_I2C1_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN I2C1_Init 0 */ 34 | 35 | /* USER CODE END I2C1_Init 0 */ 36 | 37 | /* USER CODE BEGIN I2C1_Init 1 */ 38 | 39 | /* USER CODE END I2C1_Init 1 */ 40 | hi2c1.Instance = I2C1; 41 | hi2c1.Init.ClockSpeed = 400000; 42 | hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2; 43 | hi2c1.Init.OwnAddress1 = 0; 44 | hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; 45 | hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; 46 | hi2c1.Init.OwnAddress2 = 0; 47 | hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; 48 | hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; 49 | if (HAL_I2C_Init(&hi2c1) != HAL_OK) 50 | { 51 | Error_Handler(); 52 | } 53 | /* USER CODE BEGIN I2C1_Init 2 */ 54 | 55 | /* USER CODE END I2C1_Init 2 */ 56 | 57 | } 58 | 59 | void HAL_I2C_MspInit(I2C_HandleTypeDef* i2cHandle) 60 | { 61 | 62 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 63 | if(i2cHandle->Instance==I2C1) 64 | { 65 | /* USER CODE BEGIN I2C1_MspInit 0 */ 66 | 67 | /* USER CODE END I2C1_MspInit 0 */ 68 | 69 | __HAL_RCC_GPIOB_CLK_ENABLE(); 70 | /**I2C1 GPIO Configuration 71 | PB8 ------> I2C1_SCL 72 | PB9 ------> I2C1_SDA 73 | */ 74 | GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9; 75 | GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; 76 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; 77 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 78 | 79 | __HAL_AFIO_REMAP_I2C1_ENABLE(); 80 | 81 | /* I2C1 clock enable */ 82 | __HAL_RCC_I2C1_CLK_ENABLE(); 83 | /* USER CODE BEGIN I2C1_MspInit 1 */ 84 | 85 | /* USER CODE END I2C1_MspInit 1 */ 86 | } 87 | } 88 | 89 | void HAL_I2C_MspDeInit(I2C_HandleTypeDef* i2cHandle) 90 | { 91 | 92 | if(i2cHandle->Instance==I2C1) 93 | { 94 | /* USER CODE BEGIN I2C1_MspDeInit 0 */ 95 | 96 | /* USER CODE END I2C1_MspDeInit 0 */ 97 | /* Peripheral clock disable */ 98 | __HAL_RCC_I2C1_CLK_DISABLE(); 99 | 100 | /**I2C1 GPIO Configuration 101 | PB8 ------> I2C1_SCL 102 | PB9 ------> I2C1_SDA 103 | */ 104 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_8); 105 | 106 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_9); 107 | 108 | /* USER CODE BEGIN I2C1_MspDeInit 1 */ 109 | 110 | /* USER CODE END I2C1_MspDeInit 1 */ 111 | } 112 | } 113 | 114 | /* USER CODE BEGIN 1 */ 115 | 116 | /* USER CODE END 1 */ 117 | -------------------------------------------------------------------------------- /Core/Src/spi.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file spi.c 5 | * @brief This file provides code for the configuration 6 | * of the SPI instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "spi.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | SPI_HandleTypeDef hspi1; 28 | 29 | /* SPI1 init function */ 30 | void MX_SPI1_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN SPI1_Init 0 */ 34 | 35 | /* USER CODE END SPI1_Init 0 */ 36 | 37 | /* USER CODE BEGIN SPI1_Init 1 */ 38 | 39 | /* USER CODE END SPI1_Init 1 */ 40 | hspi1.Instance = SPI1; 41 | hspi1.Init.Mode = SPI_MODE_MASTER; 42 | hspi1.Init.Direction = SPI_DIRECTION_1LINE; 43 | hspi1.Init.DataSize = SPI_DATASIZE_8BIT; 44 | hspi1.Init.CLKPolarity = SPI_POLARITY_LOW; 45 | hspi1.Init.CLKPhase = SPI_PHASE_1EDGE; 46 | hspi1.Init.NSS = SPI_NSS_SOFT; 47 | hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4; 48 | hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB; 49 | hspi1.Init.TIMode = SPI_TIMODE_DISABLE; 50 | hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE; 51 | hspi1.Init.CRCPolynomial = 10; 52 | if (HAL_SPI_Init(&hspi1) != HAL_OK) 53 | { 54 | Error_Handler(); 55 | } 56 | /* USER CODE BEGIN SPI1_Init 2 */ 57 | 58 | /* USER CODE END SPI1_Init 2 */ 59 | 60 | } 61 | 62 | void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle) 63 | { 64 | 65 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 66 | if(spiHandle->Instance==SPI1) 67 | { 68 | /* USER CODE BEGIN SPI1_MspInit 0 */ 69 | 70 | /* USER CODE END SPI1_MspInit 0 */ 71 | /* SPI1 clock enable */ 72 | __HAL_RCC_SPI1_CLK_ENABLE(); 73 | 74 | __HAL_RCC_GPIOA_CLK_ENABLE(); 75 | /**SPI1 GPIO Configuration 76 | PA5 ------> SPI1_SCK 77 | PA7 ------> SPI1_MOSI 78 | */ 79 | GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_7; 80 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 81 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; 82 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 83 | 84 | /* USER CODE BEGIN SPI1_MspInit 1 */ 85 | 86 | /* USER CODE END SPI1_MspInit 1 */ 87 | } 88 | } 89 | 90 | void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle) 91 | { 92 | 93 | if(spiHandle->Instance==SPI1) 94 | { 95 | /* USER CODE BEGIN SPI1_MspDeInit 0 */ 96 | 97 | /* USER CODE END SPI1_MspDeInit 0 */ 98 | /* Peripheral clock disable */ 99 | __HAL_RCC_SPI1_CLK_DISABLE(); 100 | 101 | /**SPI1 GPIO Configuration 102 | PA5 ------> SPI1_SCK 103 | PA7 ------> SPI1_MOSI 104 | */ 105 | HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_7); 106 | 107 | /* USER CODE BEGIN SPI1_MspDeInit 1 */ 108 | 109 | /* USER CODE END SPI1_MspDeInit 1 */ 110 | } 111 | } 112 | 113 | /* USER CODE BEGIN 1 */ 114 | 115 | /* USER CODE END 1 */ 116 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #此文件从模板自动生成! 请勿更改! 2 | set(CMAKE_SYSTEM_NAME Generic) 3 | set(CMAKE_SYSTEM_VERSION 1) 4 | cmake_minimum_required(VERSION 3.21) 5 | 6 | # specify cross compilers and tools 7 | set(CMAKE_C_COMPILER arm-none-eabi-gcc) 8 | set(CMAKE_CXX_COMPILER arm-none-eabi-g++) 9 | set(CMAKE_ASM_COMPILER arm-none-eabi-gcc) 10 | set(CMAKE_AR arm-none-eabi-ar) 11 | set(CMAKE_OBJCOPY arm-none-eabi-objcopy) 12 | set(CMAKE_OBJDUMP arm-none-eabi-objdump) 13 | set(SIZE arm-none-eabi-size) 14 | set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) 15 | 16 | # project settings 17 | project(FOC_Driver C CXX ASM) 18 | set(CMAKE_CXX_STANDARD 17) 19 | set(CMAKE_C_STANDARD 11) 20 | 21 | #Uncomment for hardware floating point 22 | #add_compile_definitions(ARM_MATH_CM4;ARM_MATH_MATRIX_CHECK;ARM_MATH_ROUNDING) 23 | #add_compile_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16) 24 | #add_link_options(-mfloat-abi=hard -mfpu=fpv4-sp-d16) 25 | 26 | #Uncomment for software floating point 27 | #add_compile_options(-mfloat-abi=soft) 28 | 29 | add_compile_options(-mcpu=cortex-m3 -mthumb -mthumb-interwork) 30 | add_compile_options(-ffunction-sections -fdata-sections -fno-common -fmessage-length=0) 31 | 32 | # uncomment to mitigate c++17 absolute addresses warnings 33 | #set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-register") 34 | 35 | # Enable assembler files preprocessing 36 | add_compile_options($<$:-x$assembler-with-cpp>) 37 | 38 | if ("${CMAKE_BUILD_TYPE}" STREQUAL "Release") 39 | message(STATUS "Maximum optimization for speed") 40 | add_compile_options(-Ofast) 41 | elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "RelWithDebInfo") 42 | message(STATUS "Maximum optimization for speed, debug info included") 43 | add_compile_options(-Ofast -g) 44 | elseif ("${CMAKE_BUILD_TYPE}" STREQUAL "MinSizeRel") 45 | message(STATUS "Maximum optimization for size") 46 | add_compile_options(-Os) 47 | else () 48 | message(STATUS "Minimal optimization, debug info included") 49 | add_compile_options(-Og -g) 50 | endif () 51 | 52 | include_directories(Core/Inc Drivers/STM32F1xx_HAL_Driver/Inc Drivers/STM32F1xx_HAL_Driver/Inc/Legacy Drivers/CMSIS/Device/ST/STM32F1xx/Include Drivers/CMSIS/Include Middlewares/Third_Party/FreeRTOS/Source/include Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM3 53 | FOC 54 | FOC/hardware_specific 55 | FOC/sensor 56 | GUI 57 | GUI/st7735 58 | BSP) 59 | 60 | add_definitions(-DDEBUG -DUSE_HAL_DRIVER -DSTM32F103xB) 61 | 62 | file(GLOB_RECURSE SOURCES "Core/*.*" "Middlewares/*.*" "Drivers/*.*" 63 | "FOC/*.*" 64 | "GUI/*.*" 65 | "BSP/*.*") 66 | 67 | set(LINKER_SCRIPT ${CMAKE_SOURCE_DIR}/STM32F103CBTX_FLASH.ld) 68 | 69 | add_link_options(-Wl,-gc-sections,--print-memory-usage,-Map=${PROJECT_BINARY_DIR}/${PROJECT_NAME}.map) 70 | add_link_options(-mcpu=cortex-m3 -mthumb -mthumb-interwork) 71 | add_link_options(-T ${LINKER_SCRIPT}) 72 | 73 | add_executable(${PROJECT_NAME}.elf ${SOURCES} ${LINKER_SCRIPT}) 74 | 75 | set(HEX_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.hex) 76 | set(BIN_FILE ${PROJECT_BINARY_DIR}/${PROJECT_NAME}.bin) 77 | 78 | add_custom_command(TARGET ${PROJECT_NAME}.elf POST_BUILD 79 | COMMAND ${CMAKE_OBJCOPY} -Oihex $ ${HEX_FILE} 80 | COMMAND ${CMAKE_OBJCOPY} -Obinary $ ${BIN_FILE} 81 | COMMENT "Building ${HEX_FILE} 82 | Building ${BIN_FILE}") 83 | -------------------------------------------------------------------------------- /Core/Src/can.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file can.c 5 | * @brief This file provides code for the configuration 6 | * of the CAN instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "can.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | CAN_HandleTypeDef hcan; 28 | 29 | /* CAN init function */ 30 | void MX_CAN_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN CAN_Init 0 */ 34 | 35 | /* USER CODE END CAN_Init 0 */ 36 | 37 | /* USER CODE BEGIN CAN_Init 1 */ 38 | 39 | /* USER CODE END CAN_Init 1 */ 40 | hcan.Instance = CAN1; 41 | hcan.Init.Prescaler = 16; 42 | hcan.Init.Mode = CAN_MODE_NORMAL; 43 | hcan.Init.SyncJumpWidth = CAN_SJW_1TQ; 44 | hcan.Init.TimeSeg1 = CAN_BS1_1TQ; 45 | hcan.Init.TimeSeg2 = CAN_BS2_1TQ; 46 | hcan.Init.TimeTriggeredMode = DISABLE; 47 | hcan.Init.AutoBusOff = DISABLE; 48 | hcan.Init.AutoWakeUp = DISABLE; 49 | hcan.Init.AutoRetransmission = DISABLE; 50 | hcan.Init.ReceiveFifoLocked = DISABLE; 51 | hcan.Init.TransmitFifoPriority = DISABLE; 52 | if (HAL_CAN_Init(&hcan) != HAL_OK) 53 | { 54 | Error_Handler(); 55 | } 56 | /* USER CODE BEGIN CAN_Init 2 */ 57 | 58 | /* USER CODE END CAN_Init 2 */ 59 | 60 | } 61 | 62 | void HAL_CAN_MspInit(CAN_HandleTypeDef* canHandle) 63 | { 64 | 65 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 66 | if(canHandle->Instance==CAN1) 67 | { 68 | /* USER CODE BEGIN CAN1_MspInit 0 */ 69 | 70 | /* USER CODE END CAN1_MspInit 0 */ 71 | /* CAN1 clock enable */ 72 | __HAL_RCC_CAN1_CLK_ENABLE(); 73 | 74 | __HAL_RCC_GPIOA_CLK_ENABLE(); 75 | /**CAN GPIO Configuration 76 | PA11 ------> CAN_RX 77 | PA12 ------> CAN_TX 78 | */ 79 | GPIO_InitStruct.Pin = GPIO_PIN_11; 80 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 81 | GPIO_InitStruct.Pull = GPIO_NOPULL; 82 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 83 | 84 | GPIO_InitStruct.Pin = GPIO_PIN_12; 85 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 86 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; 87 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 88 | 89 | /* USER CODE BEGIN CAN1_MspInit 1 */ 90 | 91 | /* USER CODE END CAN1_MspInit 1 */ 92 | } 93 | } 94 | 95 | void HAL_CAN_MspDeInit(CAN_HandleTypeDef* canHandle) 96 | { 97 | 98 | if(canHandle->Instance==CAN1) 99 | { 100 | /* USER CODE BEGIN CAN1_MspDeInit 0 */ 101 | 102 | /* USER CODE END CAN1_MspDeInit 0 */ 103 | /* Peripheral clock disable */ 104 | __HAL_RCC_CAN1_CLK_DISABLE(); 105 | 106 | /**CAN GPIO Configuration 107 | PA11 ------> CAN_RX 108 | PA12 ------> CAN_TX 109 | */ 110 | HAL_GPIO_DeInit(GPIOA, GPIO_PIN_11|GPIO_PIN_12); 111 | 112 | /* USER CODE BEGIN CAN1_MspDeInit 1 */ 113 | 114 | /* USER CODE END CAN1_MspDeInit 1 */ 115 | } 116 | } 117 | 118 | /* USER CODE BEGIN 1 */ 119 | 120 | /* USER CODE END 1 */ 121 | -------------------------------------------------------------------------------- /Core/Src/usart.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file usart.c 5 | * @brief This file provides code for the configuration 6 | * of the USART instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "usart.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | UART_HandleTypeDef huart1; 28 | 29 | /* USART1 init function */ 30 | 31 | void MX_USART1_UART_Init(void) 32 | { 33 | 34 | /* USER CODE BEGIN USART1_Init 0 */ 35 | 36 | /* USER CODE END USART1_Init 0 */ 37 | 38 | /* USER CODE BEGIN USART1_Init 1 */ 39 | 40 | /* USER CODE END USART1_Init 1 */ 41 | huart1.Instance = USART1; 42 | huart1.Init.BaudRate = 115200; 43 | huart1.Init.WordLength = UART_WORDLENGTH_8B; 44 | huart1.Init.StopBits = UART_STOPBITS_1; 45 | huart1.Init.Parity = UART_PARITY_NONE; 46 | huart1.Init.Mode = UART_MODE_TX_RX; 47 | huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE; 48 | huart1.Init.OverSampling = UART_OVERSAMPLING_16; 49 | if (HAL_UART_Init(&huart1) != HAL_OK) 50 | { 51 | Error_Handler(); 52 | } 53 | /* USER CODE BEGIN USART1_Init 2 */ 54 | 55 | /* USER CODE END USART1_Init 2 */ 56 | 57 | } 58 | 59 | void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle) 60 | { 61 | 62 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 63 | if(uartHandle->Instance==USART1) 64 | { 65 | /* USER CODE BEGIN USART1_MspInit 0 */ 66 | 67 | /* USER CODE END USART1_MspInit 0 */ 68 | /* USART1 clock enable */ 69 | __HAL_RCC_USART1_CLK_ENABLE(); 70 | 71 | __HAL_RCC_GPIOB_CLK_ENABLE(); 72 | /**USART1 GPIO Configuration 73 | PB6 ------> USART1_TX 74 | PB7 ------> USART1_RX 75 | */ 76 | GPIO_InitStruct.Pin = GPIO_PIN_6; 77 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 78 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH; 79 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 80 | 81 | GPIO_InitStruct.Pin = GPIO_PIN_7; 82 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 83 | GPIO_InitStruct.Pull = GPIO_NOPULL; 84 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 85 | 86 | __HAL_AFIO_REMAP_USART1_ENABLE(); 87 | 88 | /* USER CODE BEGIN USART1_MspInit 1 */ 89 | 90 | /* USER CODE END USART1_MspInit 1 */ 91 | } 92 | } 93 | 94 | void HAL_UART_MspDeInit(UART_HandleTypeDef* uartHandle) 95 | { 96 | 97 | if(uartHandle->Instance==USART1) 98 | { 99 | /* USER CODE BEGIN USART1_MspDeInit 0 */ 100 | 101 | /* USER CODE END USART1_MspDeInit 0 */ 102 | /* Peripheral clock disable */ 103 | __HAL_RCC_USART1_CLK_DISABLE(); 104 | 105 | /**USART1 GPIO Configuration 106 | PB6 ------> USART1_TX 107 | PB7 ------> USART1_RX 108 | */ 109 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6|GPIO_PIN_7); 110 | 111 | /* USER CODE BEGIN USART1_MspDeInit 1 */ 112 | 113 | /* USER CODE END USART1_MspDeInit 1 */ 114 | } 115 | } 116 | 117 | /* USER CODE BEGIN 1 */ 118 | 119 | /* USER CODE END 1 */ 120 | -------------------------------------------------------------------------------- /FOC/FOC_utils.c: -------------------------------------------------------------------------------- 1 | #include 2 | #include "FOC_utils.h" 3 | 4 | // int array instead of float array 5 | // 4x200 points per 360 deg 6 | // 2x storage save (int 2Byte float 4 Byte ) 7 | // sin*10000 8 | const int sine_array[200] = {0,79,158,237,316,395,473,552,631,710,789,867,946,1024,1103,1181,1260,1338,1416,1494,1572,1650,1728,1806,1883,1961,2038,2115,2192,2269,2346,2423,2499,2575,2652,2728,2804,2879,2955,3030,3105,3180,3255,3329,3404,3478,3552,3625,3699,3772,3845,3918,3990,4063,4135,4206,4278,4349,4420,4491,4561,4631,4701,4770,4840,4909,4977,5046,5113,5181,5249,5316,5382,5449,5515,5580,5646,5711,5775,5839,5903,5967,6030,6093,6155,6217,6279,6340,6401,6461,6521,6581,6640,6699,6758,6815,6873,6930,6987,7043,7099,7154,7209,7264,7318,7371,7424,7477,7529,7581,7632,7683,7733,7783,7832,7881,7930,7977,8025,8072,8118,8164,8209,8254,8298,8342,8385,8428,8470,8512,8553,8594,8634,8673,8712,8751,8789,8826,8863,8899,8935,8970,9005,9039,9072,9105,9138,9169,9201,9231,9261,9291,9320,9348,9376,9403,9429,9455,9481,9506,9530,9554,9577,9599,9621,9642,9663,9683,9702,9721,9739,9757,9774,9790,9806,9821,9836,9850,9863,9876,9888,9899,9910,9920,9930,9939,9947,9955,9962,9969,9975,9980,9985,9989,9992,9995,9997,9999,10000,10000}; 9 | 10 | // function approximating the sine calculation by using fixed size array 11 | // ~40us (float array) 12 | // ~50us (int array) 13 | // precision +-0.005 14 | // it has to receive an angle in between 0 and 2PI 15 | float _sin(float a){ 16 | if(a < _PI_2){ 17 | //return sine_array[(int)(199.0f*( a / (_PI/2.0)))]; 18 | //return sine_array[(int)(126.6873f* a)]; // float array optimized 19 | return 0.0001f*sine_array[_round(126.6873f* a)]; // int array optimized 20 | }else if(a < _PI){ 21 | // return sine_array[(int)(199.0f*(1.0f - (a-_PI/2.0) / (_PI/2.0)))]; 22 | //return sine_array[398 - (int)(126.6873f*a)]; // float array optimized 23 | return 0.0001f*sine_array[398 - _round(126.6873f*a)]; // int array optimized 24 | }else if(a < _3PI_2){ 25 | // return -sine_array[(int)(199.0f*((a - _PI) / (_PI/2.0)))]; 26 | //return -sine_array[-398 + (int)(126.6873f*a)]; // float array optimized 27 | return -0.0001f*sine_array[-398 + _round(126.6873f*a)]; // int array optimized 28 | } else { 29 | // return -sine_array[(int)(199.0f*(1.0f - (a - 3*_PI/2) / (_PI/2.0)))]; 30 | //return -sine_array[796 - (int)(126.6873f*a)]; // float array optimized 31 | return -0.0001f*sine_array[796 - _round(126.6873f*a)]; // int array optimized 32 | } 33 | } 34 | 35 | // function approximating cosine calculation by using fixed size array 36 | // ~55us (float array) 37 | // ~56us (int array) 38 | // precision +-0.005 39 | // it has to receive an angle in between 0 and 2PI 40 | float _cos(float a){ 41 | float a_sin = a + _PI_2; 42 | a_sin = a_sin > _2PI ? a_sin - _2PI : a_sin; 43 | return _sin(a_sin); 44 | } 45 | 46 | 47 | // normalizing radian angle to [0,2PI] 48 | float _normalizeAngle(float angle){ 49 | float a = fmod(angle, _2PI); 50 | return a >= 0 ? a : (a + _2PI); 51 | } 52 | 53 | // Electrical angle calculation 54 | float _electricalAngle(float shaft_angle, int pole_pairs) { 55 | return (shaft_angle * pole_pairs); 56 | } 57 | 58 | // square root approximation function using 59 | // https://reprap.org/forum/read.php?147,219210 60 | // https://en.wikipedia.org/wiki/Fast_inverse_square_root 61 | float _sqrtApprox(float number) {//low in fat 62 | long i; 63 | float y; 64 | // float x; 65 | // const float f = 1.5F; // better precision 66 | 67 | // x = number * 0.5F; 68 | y = number; 69 | i = * ( long * ) &y; 70 | i = 0x5f375a86 - ( i >> 1 ); 71 | y = * ( float * ) &i; 72 | // y = y * ( f - ( x * y * y ) ); // better precision 73 | return number * y; 74 | } -------------------------------------------------------------------------------- /Core/Src/adc.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file adc.c 5 | * @brief This file provides code for the configuration 6 | * of the ADC instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "adc.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | ADC_HandleTypeDef hadc1; 28 | 29 | /* ADC1 init function */ 30 | void MX_ADC1_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN ADC1_Init 0 */ 34 | 35 | /* USER CODE END ADC1_Init 0 */ 36 | 37 | ADC_ChannelConfTypeDef sConfig = {0}; 38 | 39 | /* USER CODE BEGIN ADC1_Init 1 */ 40 | 41 | /* USER CODE END ADC1_Init 1 */ 42 | 43 | /** Common config 44 | */ 45 | hadc1.Instance = ADC1; 46 | hadc1.Init.ScanConvMode = ADC_SCAN_ENABLE; 47 | hadc1.Init.ContinuousConvMode = DISABLE; 48 | hadc1.Init.DiscontinuousConvMode = ENABLE; 49 | hadc1.Init.NbrOfDiscConversion = 1; 50 | hadc1.Init.ExternalTrigConv = ADC_SOFTWARE_START; 51 | hadc1.Init.DataAlign = ADC_DATAALIGN_RIGHT; 52 | hadc1.Init.NbrOfConversion = 3; 53 | if (HAL_ADC_Init(&hadc1) != HAL_OK) 54 | { 55 | Error_Handler(); 56 | } 57 | 58 | /** Configure Regular Channel 59 | */ 60 | sConfig.Channel = ADC_CHANNEL_0; 61 | sConfig.Rank = ADC_REGULAR_RANK_1; 62 | sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5; 63 | if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) 64 | { 65 | Error_Handler(); 66 | } 67 | 68 | /** Configure Regular Channel 69 | */ 70 | sConfig.Channel = ADC_CHANNEL_1; 71 | sConfig.Rank = ADC_REGULAR_RANK_2; 72 | if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) 73 | { 74 | Error_Handler(); 75 | } 76 | 77 | /** Configure Regular Channel 78 | */ 79 | sConfig.Channel = ADC_CHANNEL_2; 80 | sConfig.Rank = ADC_REGULAR_RANK_3; 81 | if (HAL_ADC_ConfigChannel(&hadc1, &sConfig) != HAL_OK) 82 | { 83 | Error_Handler(); 84 | } 85 | /* USER CODE BEGIN ADC1_Init 2 */ 86 | 87 | /* USER CODE END ADC1_Init 2 */ 88 | 89 | } 90 | 91 | void HAL_ADC_MspInit(ADC_HandleTypeDef* adcHandle) 92 | { 93 | 94 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 95 | if(adcHandle->Instance==ADC1) 96 | { 97 | /* USER CODE BEGIN ADC1_MspInit 0 */ 98 | 99 | /* USER CODE END ADC1_MspInit 0 */ 100 | /* ADC1 clock enable */ 101 | __HAL_RCC_ADC1_CLK_ENABLE(); 102 | 103 | __HAL_RCC_GPIOA_CLK_ENABLE(); 104 | /**ADC1 GPIO Configuration 105 | PA0-WKUP ------> ADC1_IN0 106 | PA1 ------> ADC1_IN1 107 | PA2 ------> ADC1_IN2 108 | */ 109 | GPIO_InitStruct.Pin = CS1_Pin|CS2_Pin|CS3_Pin; 110 | GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; 111 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 112 | 113 | /* USER CODE BEGIN ADC1_MspInit 1 */ 114 | 115 | /* USER CODE END ADC1_MspInit 1 */ 116 | } 117 | } 118 | 119 | void HAL_ADC_MspDeInit(ADC_HandleTypeDef* adcHandle) 120 | { 121 | 122 | if(adcHandle->Instance==ADC1) 123 | { 124 | /* USER CODE BEGIN ADC1_MspDeInit 0 */ 125 | 126 | /* USER CODE END ADC1_MspDeInit 0 */ 127 | /* Peripheral clock disable */ 128 | __HAL_RCC_ADC1_CLK_DISABLE(); 129 | 130 | /**ADC1 GPIO Configuration 131 | PA0-WKUP ------> ADC1_IN0 132 | PA1 ------> ADC1_IN1 133 | PA2 ------> ADC1_IN2 134 | */ 135 | HAL_GPIO_DeInit(GPIOA, CS1_Pin|CS2_Pin|CS3_Pin); 136 | 137 | /* USER CODE BEGIN ADC1_MspDeInit 1 */ 138 | 139 | /* USER CODE END ADC1_MspDeInit 1 */ 140 | } 141 | } 142 | 143 | /* USER CODE BEGIN 1 */ 144 | 145 | /* USER CODE END 1 */ 146 | -------------------------------------------------------------------------------- /Drivers/STM32F1xx_HAL_Driver/Src/stm32f1xx_hal_gpio_ex.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f1xx_hal_gpio_ex.c 4 | * @author MCD Application Team 5 | * @brief GPIO Extension HAL module driver. 6 | * This file provides firmware functions to manage the following 7 | * functionalities of the General Purpose Input/Output (GPIO) extension peripheral. 8 | * + Extended features functions 9 | * 10 | @verbatim 11 | ============================================================================== 12 | ##### GPIO Peripheral extension features ##### 13 | ============================================================================== 14 | [..] GPIO module on STM32F1 family, manage also the AFIO register: 15 | (+) Possibility to use the EVENTOUT Cortex feature 16 | 17 | ##### How to use this driver ##### 18 | ============================================================================== 19 | [..] This driver provides functions to use EVENTOUT Cortex feature 20 | (#) Configure EVENTOUT Cortex feature using the function HAL_GPIOEx_ConfigEventout() 21 | (#) Activate EVENTOUT Cortex feature using the HAL_GPIOEx_EnableEventout() 22 | (#) Deactivate EVENTOUT Cortex feature using the HAL_GPIOEx_DisableEventout() 23 | 24 | @endverbatim 25 | ****************************************************************************** 26 | * @attention 27 | * 28 | *

© Copyright (c) 2016 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 "stm32f1xx_hal.h" 41 | 42 | /** @addtogroup STM32F1xx_HAL_Driver 43 | * @{ 44 | */ 45 | 46 | /** @defgroup GPIOEx GPIOEx 47 | * @brief GPIO HAL module driver 48 | * @{ 49 | */ 50 | 51 | #ifdef HAL_GPIO_MODULE_ENABLED 52 | 53 | /** @defgroup GPIOEx_Exported_Functions GPIOEx Exported Functions 54 | * @{ 55 | */ 56 | 57 | /** @defgroup GPIOEx_Exported_Functions_Group1 Extended features functions 58 | * @brief Extended features functions 59 | * 60 | @verbatim 61 | ============================================================================== 62 | ##### Extended features functions ##### 63 | ============================================================================== 64 | [..] This section provides functions allowing to: 65 | (+) Configure EVENTOUT Cortex feature using the function HAL_GPIOEx_ConfigEventout() 66 | (+) Activate EVENTOUT Cortex feature using the HAL_GPIOEx_EnableEventout() 67 | (+) Deactivate EVENTOUT Cortex feature using the HAL_GPIOEx_DisableEventout() 68 | 69 | @endverbatim 70 | * @{ 71 | */ 72 | 73 | /** 74 | * @brief Configures the port and pin on which the EVENTOUT Cortex signal will be connected. 75 | * @param GPIO_PortSource Select the port used to output the Cortex EVENTOUT signal. 76 | * This parameter can be a value of @ref GPIOEx_EVENTOUT_PORT. 77 | * @param GPIO_PinSource Select the pin used to output the Cortex EVENTOUT signal. 78 | * This parameter can be a value of @ref GPIOEx_EVENTOUT_PIN. 79 | * @retval None 80 | */ 81 | void HAL_GPIOEx_ConfigEventout(uint32_t GPIO_PortSource, uint32_t GPIO_PinSource) 82 | { 83 | /* Verify the parameters */ 84 | assert_param(IS_AFIO_EVENTOUT_PORT(GPIO_PortSource)); 85 | assert_param(IS_AFIO_EVENTOUT_PIN(GPIO_PinSource)); 86 | 87 | /* Apply the new configuration */ 88 | MODIFY_REG(AFIO->EVCR, (AFIO_EVCR_PORT) | (AFIO_EVCR_PIN), (GPIO_PortSource) | (GPIO_PinSource)); 89 | } 90 | 91 | /** 92 | * @brief Enables the Event Output. 93 | * @retval None 94 | */ 95 | void HAL_GPIOEx_EnableEventout(void) 96 | { 97 | SET_BIT(AFIO->EVCR, AFIO_EVCR_EVOE); 98 | } 99 | 100 | /** 101 | * @brief Disables the Event Output. 102 | * @retval None 103 | */ 104 | void HAL_GPIOEx_DisableEventout(void) 105 | { 106 | CLEAR_BIT(AFIO->EVCR, AFIO_EVCR_EVOE); 107 | } 108 | 109 | /** 110 | * @} 111 | */ 112 | 113 | /** 114 | * @} 115 | */ 116 | 117 | #endif /* HAL_GPIO_MODULE_ENABLED */ 118 | 119 | /** 120 | * @} 121 | */ 122 | 123 | /** 124 | * @} 125 | */ 126 | 127 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 128 | -------------------------------------------------------------------------------- /FOC/FOC_PID.c: -------------------------------------------------------------------------------- 1 | #include "FOC_PID.h" 2 | #include "math.h" 3 | 4 | PID_Datatype pid_velocity; 5 | PID_Datatype pid_position; 6 | PID_Datatype pid_spring; 7 | PID_Datatype pid_spring_with_damp; 8 | PID_Datatype pid_damp; 9 | PID_Datatype pid_zero_resistance; 10 | PID_Datatype pid_knob; 11 | 12 | PID_Datatype pid_current_d; 13 | PID_Datatype pid_current_q; 14 | 15 | void pid_set_parameters() { 16 | pid_velocity.Kp = 0.08; 17 | pid_velocity.Ki = 0.03; // 0.03 18 | pid_velocity.Kd = 0; 19 | pid_velocity.integral = 0; 20 | pid_velocity.last_error = 0; 21 | pid_velocity.max_integral = 500.0; // 200 22 | pid_velocity.min_integral = -500.0; 23 | pid_velocity.max_u = 8.0; 24 | pid_velocity.min_u = -8.0; 25 | pid_velocity.dead_zone = 0; 26 | 27 | pid_position.Kp = 10.0; // 20.0 28 | pid_position.Ki = 0.0; 29 | pid_position.Kd = 0; 30 | pid_position.integral = 0; 31 | pid_position.last_error = 0; 32 | pid_position.max_integral = 0.0; 33 | pid_position.min_integral = -0.0; 34 | pid_position.max_u = 20.0; 35 | pid_position.min_u = -20.0; 36 | pid_position.dead_zone = 0.0; 37 | 38 | pid_spring.Kp = 2.5; 39 | pid_spring.Ki = 0.0; 40 | pid_spring.Kd = -32; 41 | pid_spring.integral = 0; 42 | pid_spring.last_error = 0; 43 | pid_spring.max_integral = 0.0; 44 | pid_spring.min_integral = -0.0; 45 | pid_spring.max_u = 2.0; 46 | pid_spring.min_u = -2.0; 47 | pid_spring.dead_zone = 0.0; 48 | 49 | pid_spring_with_damp.Kp = 2.5; 50 | pid_spring_with_damp.Ki = 0.0; 51 | pid_spring_with_damp.Kd = 150; 52 | pid_spring_with_damp.integral = 0; 53 | pid_spring_with_damp.last_error = 0; 54 | pid_spring_with_damp.max_integral = 0.0; 55 | pid_spring_with_damp.min_integral = -0.0; 56 | pid_spring_with_damp.max_u = 2.0; 57 | pid_spring_with_damp.min_u = -2.0; 58 | pid_spring_with_damp.dead_zone = 0.0; 59 | 60 | pid_damp.Kp = 0.0; 61 | pid_damp.Ki = 0.0; 62 | pid_damp.Kd = 200; 63 | pid_damp.integral = 0; 64 | pid_damp.last_error = 0; 65 | pid_damp.max_integral = 0.0; 66 | pid_damp.min_integral = -0.0; 67 | pid_damp.max_u = 8.0; 68 | pid_damp.min_u = -8.0; 69 | pid_damp.dead_zone = 0.0; 70 | 71 | pid_zero_resistance.Kp = 0.0; 72 | pid_zero_resistance.Ki = 0.0; 73 | pid_zero_resistance.Kd = -30.5; 74 | pid_zero_resistance.integral = 0; 75 | pid_zero_resistance.last_error = 0; 76 | pid_zero_resistance.max_integral = 0.0; 77 | pid_zero_resistance.min_integral = -0.0; 78 | pid_zero_resistance.max_u = 2.0; 79 | pid_zero_resistance.min_u = -2.0; 80 | pid_zero_resistance.dead_zone = 0.0; 81 | 82 | pid_knob.Kp = 5.0; 83 | pid_knob.Ki = 0.0; 84 | pid_knob.Kd = 0; 85 | pid_knob.integral = 0; 86 | pid_knob.last_error = 0; 87 | pid_knob.max_integral = 0.0; 88 | pid_knob.min_integral = -0.0; 89 | pid_knob.max_u = 4.0; 90 | pid_knob.min_u = -4.0; 91 | pid_knob.dead_zone = 0.0; 92 | 93 | pid_current_d.Kp = 0.004; 94 | pid_current_d.Ki = 0.0; 95 | pid_current_d.Kd = 0; 96 | pid_current_d.integral = 0; 97 | pid_current_d.last_error = 0; 98 | pid_current_d.max_integral = 200.0; 99 | pid_current_d.min_integral = -200.0; 100 | pid_current_d.max_u = 8.0; 101 | pid_current_d.min_u = -8.0; 102 | pid_current_d.dead_zone = 0.0; 103 | 104 | pid_current_q.Kp = 0.004; 105 | pid_current_q.Ki = 0.0; 106 | pid_current_q.Kd = 0; 107 | pid_current_q.integral = 0; 108 | pid_current_q.last_error = 0; 109 | pid_current_q.max_integral = 200.0; 110 | pid_current_q.min_integral = -200.0; 111 | pid_current_q.max_u = 8.0; 112 | pid_current_q.min_u = -8.0; 113 | pid_current_q.dead_zone = 0.0; 114 | } 115 | 116 | /** 117 | * @brief 获取pid的控制量u 118 | * @param pid 119 | * @param target 120 | * @param real 121 | * @return u 122 | */ 123 | float pid_get_u(PID_Datatype *pid, float target, float real) { 124 | float error = target - real; // 误差 125 | 126 | if (fabs(error) < pid->dead_zone) error = 0; // 死区 127 | 128 | pid->integral += error; // 积分误差 129 | // if (fabs(pid->integral) < pid->dead_zone) pid->integral = 0; // 死区 130 | 131 | if (pid->integral > pid->max_integral) { // 设置积分误差的上下限,防止过大或过小 132 | pid->integral = pid->max_integral; 133 | } else if (pid->integral < pid->min_integral) { 134 | pid->integral = pid->min_integral; 135 | } 136 | 137 | double differential = error - pid->last_error; // 差分误差 138 | // if (fabs(differential) < pid->dead_zone) differential = 0; // 死区 139 | 140 | double u = pid->Kp * error + pid->Ki * pid->integral + pid->Kd * differential; // 控制量 141 | if (u > pid->max_u) { // 设置控制量u的上下限,防止过大或过小 142 | u = pid->max_u; 143 | } else if (u < pid->min_u) { 144 | u = pid->min_u; 145 | } 146 | 147 | pid->last_error = error; // 记录下本轮误差供下次差分使用 148 | 149 | return u; 150 | } 151 | -------------------------------------------------------------------------------- /Core/Src/stm32f1xx_hal_timebase_tim.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32f1xx_hal_timebase_TIM.c 5 | * @brief HAL time base based on the hardware TIM. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2022 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file 13 | * in the root directory of this software component. 14 | * If no LICENSE file comes with this software, it is provided AS-IS. 15 | * 16 | ****************************************************************************** 17 | */ 18 | /* USER CODE END Header */ 19 | 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "stm32f1xx_hal.h" 22 | #include "stm32f1xx_hal_tim.h" 23 | 24 | /* Private typedef -----------------------------------------------------------*/ 25 | /* Private define ------------------------------------------------------------*/ 26 | /* Private macro -------------------------------------------------------------*/ 27 | /* Private variables ---------------------------------------------------------*/ 28 | TIM_HandleTypeDef htim4; 29 | /* Private function prototypes -----------------------------------------------*/ 30 | void TIM4_IRQHandler(void); 31 | /* Private functions ---------------------------------------------------------*/ 32 | 33 | /** 34 | * @brief This function configures the TIM4 as a time base source. 35 | * The time source is configured to have 1ms time base with a dedicated 36 | * Tick interrupt priority. 37 | * @note This function is called automatically at the beginning of program after 38 | * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig(). 39 | * @param TickPriority: Tick interrupt priority. 40 | * @retval HAL status 41 | */ 42 | HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority) 43 | { 44 | RCC_ClkInitTypeDef clkconfig; 45 | uint32_t uwTimclock, uwAPB1Prescaler = 0U; 46 | 47 | uint32_t uwPrescalerValue = 0U; 48 | uint32_t pFLatency; 49 | HAL_StatusTypeDef status = HAL_OK; 50 | 51 | /* Enable TIM4 clock */ 52 | __HAL_RCC_TIM4_CLK_ENABLE(); 53 | 54 | /* Get clock configuration */ 55 | HAL_RCC_GetClockConfig(&clkconfig, &pFLatency); 56 | 57 | /* Get APB1 prescaler */ 58 | uwAPB1Prescaler = clkconfig.APB1CLKDivider; 59 | /* Compute TIM4 clock */ 60 | if (uwAPB1Prescaler == RCC_HCLK_DIV1) 61 | { 62 | uwTimclock = HAL_RCC_GetPCLK1Freq(); 63 | } 64 | else 65 | { 66 | uwTimclock = 2UL * HAL_RCC_GetPCLK1Freq(); 67 | } 68 | 69 | /* Compute the prescaler value to have TIM4 counter clock equal to 1MHz */ 70 | uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000U) - 1U); 71 | 72 | /* Initialize TIM4 */ 73 | htim4.Instance = TIM4; 74 | 75 | /* Initialize TIMx peripheral as follow: 76 | + Period = [(TIM4CLK/1000) - 1]. to have a (1/1000) s time base. 77 | + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock. 78 | + ClockDivision = 0 79 | + Counter direction = Up 80 | */ 81 | htim4.Init.Period = (1000000U / 1000U) - 1U; 82 | htim4.Init.Prescaler = uwPrescalerValue; 83 | htim4.Init.ClockDivision = 0; 84 | htim4.Init.CounterMode = TIM_COUNTERMODE_UP; 85 | htim4.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; 86 | 87 | status = HAL_TIM_Base_Init(&htim4); 88 | if (status == HAL_OK) 89 | { 90 | /* Start the TIM time Base generation in interrupt mode */ 91 | status = HAL_TIM_Base_Start_IT(&htim4); 92 | if (status == HAL_OK) 93 | { 94 | /* Enable the TIM4 global Interrupt */ 95 | HAL_NVIC_EnableIRQ(TIM4_IRQn); 96 | /* Configure the SysTick IRQ priority */ 97 | if (TickPriority < (1UL << __NVIC_PRIO_BITS)) 98 | { 99 | /* Configure the TIM IRQ priority */ 100 | HAL_NVIC_SetPriority(TIM4_IRQn, TickPriority, 0U); 101 | uwTickPrio = TickPriority; 102 | } 103 | else 104 | { 105 | status = HAL_ERROR; 106 | } 107 | } 108 | } 109 | 110 | /* Return function status */ 111 | return status; 112 | } 113 | 114 | /** 115 | * @brief Suspend Tick increment. 116 | * @note Disable the tick increment by disabling TIM4 update interrupt. 117 | * @param None 118 | * @retval None 119 | */ 120 | void HAL_SuspendTick(void) 121 | { 122 | /* Disable TIM4 update Interrupt */ 123 | __HAL_TIM_DISABLE_IT(&htim4, TIM_IT_UPDATE); 124 | } 125 | 126 | /** 127 | * @brief Resume Tick increment. 128 | * @note Enable the tick increment by Enabling TIM4 update interrupt. 129 | * @param None 130 | * @retval None 131 | */ 132 | void HAL_ResumeTick(void) 133 | { 134 | /* Enable TIM4 Update interrupt */ 135 | __HAL_TIM_ENABLE_IT(&htim4, TIM_IT_UPDATE); 136 | } 137 | 138 | -------------------------------------------------------------------------------- /Core/Src/tim.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file tim.c 5 | * @brief This file provides code for the configuration 6 | * of the TIM instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2022 STMicroelectronics. 11 | * All rights reserved. 12 | * 13 | * This software is licensed under terms that can be found in the LICENSE file 14 | * in the root directory of this software component. 15 | * If no LICENSE file comes with this software, it is provided AS-IS. 16 | * 17 | ****************************************************************************** 18 | */ 19 | /* USER CODE END Header */ 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "tim.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | TIM_HandleTypeDef htim1; 28 | 29 | /* TIM1 init function */ 30 | void MX_TIM1_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN TIM1_Init 0 */ 34 | 35 | /* USER CODE END TIM1_Init 0 */ 36 | 37 | TIM_ClockConfigTypeDef sClockSourceConfig = {0}; 38 | TIM_MasterConfigTypeDef sMasterConfig = {0}; 39 | TIM_OC_InitTypeDef sConfigOC = {0}; 40 | TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0}; 41 | 42 | /* USER CODE BEGIN TIM1_Init 1 */ 43 | 44 | /* USER CODE END TIM1_Init 1 */ 45 | htim1.Instance = TIM1; 46 | htim1.Init.Prescaler = 0; 47 | htim1.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED2; 48 | htim1.Init.Period = 4096-1; 49 | htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; 50 | htim1.Init.RepetitionCounter = 0; 51 | htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; 52 | if (HAL_TIM_Base_Init(&htim1) != HAL_OK) 53 | { 54 | Error_Handler(); 55 | } 56 | sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL; 57 | if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK) 58 | { 59 | Error_Handler(); 60 | } 61 | if (HAL_TIM_PWM_Init(&htim1) != HAL_OK) 62 | { 63 | Error_Handler(); 64 | } 65 | sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET; 66 | sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; 67 | if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK) 68 | { 69 | Error_Handler(); 70 | } 71 | sConfigOC.OCMode = TIM_OCMODE_PWM1; 72 | sConfigOC.Pulse = 0; 73 | sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; 74 | sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH; 75 | sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; 76 | sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; 77 | sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET; 78 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_1) != HAL_OK) 79 | { 80 | Error_Handler(); 81 | } 82 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK) 83 | { 84 | Error_Handler(); 85 | } 86 | if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK) 87 | { 88 | Error_Handler(); 89 | } 90 | sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE; 91 | sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE; 92 | sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; 93 | sBreakDeadTimeConfig.DeadTime = 0; 94 | sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; 95 | sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH; 96 | sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; 97 | if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK) 98 | { 99 | Error_Handler(); 100 | } 101 | /* USER CODE BEGIN TIM1_Init 2 */ 102 | 103 | /* USER CODE END TIM1_Init 2 */ 104 | HAL_TIM_MspPostInit(&htim1); 105 | 106 | } 107 | 108 | void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle) 109 | { 110 | 111 | if(tim_baseHandle->Instance==TIM1) 112 | { 113 | /* USER CODE BEGIN TIM1_MspInit 0 */ 114 | 115 | /* USER CODE END TIM1_MspInit 0 */ 116 | /* TIM1 clock enable */ 117 | __HAL_RCC_TIM1_CLK_ENABLE(); 118 | /* USER CODE BEGIN TIM1_MspInit 1 */ 119 | 120 | /* USER CODE END TIM1_MspInit 1 */ 121 | } 122 | } 123 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle) 124 | { 125 | 126 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 127 | if(timHandle->Instance==TIM1) 128 | { 129 | /* USER CODE BEGIN TIM1_MspPostInit 0 */ 130 | 131 | /* USER CODE END TIM1_MspPostInit 0 */ 132 | 133 | __HAL_RCC_GPIOA_CLK_ENABLE(); 134 | /**TIM1 GPIO Configuration 135 | PA8 ------> TIM1_CH1 136 | PA9 ------> TIM1_CH2 137 | PA10 ------> TIM1_CH3 138 | */ 139 | GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9|GPIO_PIN_10; 140 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 141 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 142 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 143 | 144 | /* USER CODE BEGIN TIM1_MspPostInit 1 */ 145 | 146 | /* USER CODE END TIM1_MspPostInit 1 */ 147 | } 148 | 149 | } 150 | 151 | void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle) 152 | { 153 | 154 | if(tim_baseHandle->Instance==TIM1) 155 | { 156 | /* USER CODE BEGIN TIM1_MspDeInit 0 */ 157 | 158 | /* USER CODE END TIM1_MspDeInit 0 */ 159 | /* Peripheral clock disable */ 160 | __HAL_RCC_TIM1_CLK_DISABLE(); 161 | /* USER CODE BEGIN TIM1_MspDeInit 1 */ 162 | 163 | /* USER CODE END TIM1_MspDeInit 1 */ 164 | } 165 | } 166 | 167 | /* USER CODE BEGIN 1 */ 168 | 169 | /* USER CODE END 1 */ 170 | -------------------------------------------------------------------------------- /STM32F103CBTX_FLASH.ld: -------------------------------------------------------------------------------- 1 | /* 2 | ****************************************************************************** 3 | ** 4 | ** @file : LinkerScript.ld 5 | ** 6 | ** @author : Auto-generated by STM32CubeIDE 7 | ** 8 | ** @brief : Linker script for STM32F103CBTx Device from STM32F1 series 9 | ** 128Kbytes FLASH 10 | ** 20Kbytes RAM 11 | ** 12 | ** Set heap size, stack size and stack location according 13 | ** to application requirements. 14 | ** 15 | ** Set memory bank area and size if external memory is used 16 | ** 17 | ** Target : STMicroelectronics STM32 18 | ** 19 | ** Distribution: The file is distributed as is, without any warranty 20 | ** of any kind. 21 | ** 22 | ****************************************************************************** 23 | ** @attention 24 | ** 25 | ** Copyright (c) 2022 STMicroelectronics. 26 | ** All rights reserved. 27 | ** 28 | ** This software is licensed under terms that can be found in the LICENSE file 29 | ** in the root directory of this software component. 30 | ** If no LICENSE file comes with this software, it is provided AS-IS. 31 | ** 32 | ****************************************************************************** 33 | */ 34 | 35 | /* Entry Point */ 36 | ENTRY(Reset_Handler) 37 | 38 | /* Highest address of the user mode stack */ 39 | _estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */ 40 | 41 | _Min_Heap_Size = 0x200 ; /* required amount of heap */ 42 | _Min_Stack_Size = 0x400 ; /* required amount of stack */ 43 | 44 | /* Memories definition */ 45 | MEMORY 46 | { 47 | RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 20K 48 | FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 128K 49 | } 50 | 51 | /* Sections */ 52 | SECTIONS 53 | { 54 | /* The startup code into "FLASH" Rom type memory */ 55 | .isr_vector : 56 | { 57 | . = ALIGN(4); 58 | KEEP(*(.isr_vector)) /* Startup code */ 59 | . = ALIGN(4); 60 | } >FLASH 61 | 62 | /* The program code and other data into "FLASH" Rom type memory */ 63 | .text : 64 | { 65 | . = ALIGN(4); 66 | *(.text) /* .text sections (code) */ 67 | *(.text*) /* .text* sections (code) */ 68 | *(.glue_7) /* glue arm to thumb code */ 69 | *(.glue_7t) /* glue thumb to arm code */ 70 | *(.eh_frame) 71 | 72 | KEEP (*(.init)) 73 | KEEP (*(.fini)) 74 | 75 | . = ALIGN(4); 76 | _etext = .; /* define a global symbols at end of code */ 77 | } >FLASH 78 | 79 | /* Constant data into "FLASH" Rom type memory */ 80 | .rodata : 81 | { 82 | . = ALIGN(4); 83 | *(.rodata) /* .rodata sections (constants, strings, etc.) */ 84 | *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ 85 | . = ALIGN(4); 86 | } >FLASH 87 | 88 | .ARM.extab : { 89 | . = ALIGN(4); 90 | *(.ARM.extab* .gnu.linkonce.armextab.*) 91 | . = ALIGN(4); 92 | } >FLASH 93 | 94 | .ARM : { 95 | . = ALIGN(4); 96 | __exidx_start = .; 97 | *(.ARM.exidx*) 98 | __exidx_end = .; 99 | . = ALIGN(4); 100 | } >FLASH 101 | 102 | .preinit_array : 103 | { 104 | . = ALIGN(4); 105 | PROVIDE_HIDDEN (__preinit_array_start = .); 106 | KEEP (*(.preinit_array*)) 107 | PROVIDE_HIDDEN (__preinit_array_end = .); 108 | . = ALIGN(4); 109 | } >FLASH 110 | 111 | .init_array : 112 | { 113 | . = ALIGN(4); 114 | PROVIDE_HIDDEN (__init_array_start = .); 115 | KEEP (*(SORT(.init_array.*))) 116 | KEEP (*(.init_array*)) 117 | PROVIDE_HIDDEN (__init_array_end = .); 118 | . = ALIGN(4); 119 | } >FLASH 120 | 121 | .fini_array : 122 | { 123 | . = ALIGN(4); 124 | PROVIDE_HIDDEN (__fini_array_start = .); 125 | KEEP (*(SORT(.fini_array.*))) 126 | KEEP (*(.fini_array*)) 127 | PROVIDE_HIDDEN (__fini_array_end = .); 128 | . = ALIGN(4); 129 | } >FLASH 130 | 131 | /* Used by the startup to initialize data */ 132 | _sidata = LOADADDR(.data); 133 | 134 | /* Initialized data sections into "RAM" Ram type memory */ 135 | .data : 136 | { 137 | . = ALIGN(4); 138 | _sdata = .; /* create a global symbol at data start */ 139 | *(.data) /* .data sections */ 140 | *(.data*) /* .data* sections */ 141 | *(.RamFunc) /* .RamFunc sections */ 142 | *(.RamFunc*) /* .RamFunc* sections */ 143 | 144 | . = ALIGN(4); 145 | _edata = .; /* define a global symbol at data end */ 146 | 147 | } >RAM AT> FLASH 148 | 149 | /* Uninitialized data section into "RAM" Ram type memory */ 150 | . = ALIGN(4); 151 | .bss : 152 | { 153 | /* This is used by the startup in order to initialize the .bss section */ 154 | _sbss = .; /* define a global symbol at bss start */ 155 | __bss_start__ = _sbss; 156 | *(.bss) 157 | *(.bss*) 158 | *(COMMON) 159 | 160 | . = ALIGN(4); 161 | _ebss = .; /* define a global symbol at bss end */ 162 | __bss_end__ = _ebss; 163 | } >RAM 164 | 165 | /* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */ 166 | ._user_heap_stack : 167 | { 168 | . = ALIGN(8); 169 | PROVIDE ( end = . ); 170 | PROVIDE ( _end = . ); 171 | . = . + _Min_Heap_Size; 172 | . = . + _Min_Stack_Size; 173 | . = ALIGN(8); 174 | } >RAM 175 | 176 | /* Remove information from the compiler libraries */ 177 | /DISCARD/ : 178 | { 179 | libc.a ( * ) 180 | libm.a ( * ) 181 | libgcc.a ( * ) 182 | } 183 | 184 | .ARM.attributes 0 : { *(.ARM.attributes) } 185 | } 186 | -------------------------------------------------------------------------------- /Core/Src/stm32f1xx_it.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32f1xx_it.c 5 | * @brief Interrupt Service Routines. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2022 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file 13 | * in the root directory of this software component. 14 | * If no LICENSE file comes with this software, it is provided AS-IS. 15 | * 16 | ****************************************************************************** 17 | */ 18 | /* USER CODE END Header */ 19 | 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "main.h" 22 | #include "stm32f1xx_it.h" 23 | /* Private includes ----------------------------------------------------------*/ 24 | /* USER CODE BEGIN Includes */ 25 | /* USER CODE END Includes */ 26 | 27 | /* Private typedef -----------------------------------------------------------*/ 28 | /* USER CODE BEGIN TD */ 29 | 30 | /* USER CODE END TD */ 31 | 32 | /* Private define ------------------------------------------------------------*/ 33 | /* USER CODE BEGIN PD */ 34 | 35 | /* USER CODE END PD */ 36 | 37 | /* Private macro -------------------------------------------------------------*/ 38 | /* USER CODE BEGIN PM */ 39 | 40 | /* USER CODE END PM */ 41 | 42 | /* Private variables ---------------------------------------------------------*/ 43 | /* USER CODE BEGIN PV */ 44 | 45 | /* USER CODE END PV */ 46 | 47 | /* Private function prototypes -----------------------------------------------*/ 48 | /* USER CODE BEGIN PFP */ 49 | 50 | /* USER CODE END PFP */ 51 | 52 | /* Private user code ---------------------------------------------------------*/ 53 | /* USER CODE BEGIN 0 */ 54 | 55 | /* USER CODE END 0 */ 56 | 57 | /* External variables --------------------------------------------------------*/ 58 | extern TIM_HandleTypeDef htim4; 59 | 60 | /* USER CODE BEGIN EV */ 61 | 62 | /* USER CODE END EV */ 63 | 64 | /******************************************************************************/ 65 | /* Cortex-M3 Processor Interruption and Exception Handlers */ 66 | /******************************************************************************/ 67 | /** 68 | * @brief This function handles Non maskable interrupt. 69 | */ 70 | void NMI_Handler(void) 71 | { 72 | /* USER CODE BEGIN NonMaskableInt_IRQn 0 */ 73 | 74 | /* USER CODE END NonMaskableInt_IRQn 0 */ 75 | /* USER CODE BEGIN NonMaskableInt_IRQn 1 */ 76 | while (1) 77 | { 78 | } 79 | /* USER CODE END NonMaskableInt_IRQn 1 */ 80 | } 81 | 82 | /** 83 | * @brief This function handles Hard fault interrupt. 84 | */ 85 | void HardFault_Handler(void) 86 | { 87 | /* USER CODE BEGIN HardFault_IRQn 0 */ 88 | 89 | /* USER CODE END HardFault_IRQn 0 */ 90 | while (1) 91 | { 92 | /* USER CODE BEGIN W1_HardFault_IRQn 0 */ 93 | /* USER CODE END W1_HardFault_IRQn 0 */ 94 | } 95 | } 96 | 97 | /** 98 | * @brief This function handles Memory management fault. 99 | */ 100 | void MemManage_Handler(void) 101 | { 102 | /* USER CODE BEGIN MemoryManagement_IRQn 0 */ 103 | 104 | /* USER CODE END MemoryManagement_IRQn 0 */ 105 | while (1) 106 | { 107 | /* USER CODE BEGIN W1_MemoryManagement_IRQn 0 */ 108 | /* USER CODE END W1_MemoryManagement_IRQn 0 */ 109 | } 110 | } 111 | 112 | /** 113 | * @brief This function handles Prefetch fault, memory access fault. 114 | */ 115 | void BusFault_Handler(void) 116 | { 117 | /* USER CODE BEGIN BusFault_IRQn 0 */ 118 | 119 | /* USER CODE END BusFault_IRQn 0 */ 120 | while (1) 121 | { 122 | /* USER CODE BEGIN W1_BusFault_IRQn 0 */ 123 | /* USER CODE END W1_BusFault_IRQn 0 */ 124 | } 125 | } 126 | 127 | /** 128 | * @brief This function handles Undefined instruction or illegal state. 129 | */ 130 | void UsageFault_Handler(void) 131 | { 132 | /* USER CODE BEGIN UsageFault_IRQn 0 */ 133 | 134 | /* USER CODE END UsageFault_IRQn 0 */ 135 | while (1) 136 | { 137 | /* USER CODE BEGIN W1_UsageFault_IRQn 0 */ 138 | /* USER CODE END W1_UsageFault_IRQn 0 */ 139 | } 140 | } 141 | 142 | /** 143 | * @brief This function handles Debug monitor. 144 | */ 145 | void DebugMon_Handler(void) 146 | { 147 | /* USER CODE BEGIN DebugMonitor_IRQn 0 */ 148 | 149 | /* USER CODE END DebugMonitor_IRQn 0 */ 150 | /* USER CODE BEGIN DebugMonitor_IRQn 1 */ 151 | 152 | /* USER CODE END DebugMonitor_IRQn 1 */ 153 | } 154 | 155 | /******************************************************************************/ 156 | /* STM32F1xx Peripheral Interrupt Handlers */ 157 | /* Add here the Interrupt Handlers for the used peripherals. */ 158 | /* For the available peripheral interrupt handler names, */ 159 | /* please refer to the startup file (startup_stm32f1xx.s). */ 160 | /******************************************************************************/ 161 | 162 | /** 163 | * @brief This function handles TIM4 global interrupt. 164 | */ 165 | void TIM4_IRQHandler(void) 166 | { 167 | /* USER CODE BEGIN TIM4_IRQn 0 */ 168 | 169 | /* USER CODE END TIM4_IRQn 0 */ 170 | HAL_TIM_IRQHandler(&htim4); 171 | /* USER CODE BEGIN TIM4_IRQn 1 */ 172 | 173 | /* USER CODE END TIM4_IRQn 1 */ 174 | } 175 | 176 | /** 177 | * @brief This function handles EXTI line[15:10] interrupts. 178 | */ 179 | void EXTI15_10_IRQHandler(void) 180 | { 181 | /* USER CODE BEGIN EXTI15_10_IRQn 0 */ 182 | 183 | /* USER CODE END EXTI15_10_IRQn 0 */ 184 | HAL_GPIO_EXTI_IRQHandler(KEY1_Pin); 185 | HAL_GPIO_EXTI_IRQHandler(KEY2_Pin); 186 | HAL_GPIO_EXTI_IRQHandler(KEY3_Pin); 187 | HAL_GPIO_EXTI_IRQHandler(KEY4_Pin); 188 | /* USER CODE BEGIN EXTI15_10_IRQn 1 */ 189 | 190 | /* USER CODE END EXTI15_10_IRQn 1 */ 191 | } 192 | 193 | /* USER CODE BEGIN 1 */ 194 | 195 | /* USER CODE END 1 */ 196 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/projdefs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef PROJDEFS_H 29 | #define PROJDEFS_H 30 | 31 | /* 32 | * Defines the prototype to which task functions must conform. Defined in this 33 | * file to ensure the type is known before portable.h is included. 34 | */ 35 | typedef void (*TaskFunction_t)( void * ); 36 | 37 | /* Converts a time in milliseconds to a time in ticks. This macro can be 38 | overridden by a macro of the same name defined in FreeRTOSConfig.h in case the 39 | definition here is not suitable for your application. */ 40 | #ifndef pdMS_TO_TICKS 41 | #define pdMS_TO_TICKS( xTimeInMs ) ( ( TickType_t ) ( ( ( TickType_t ) ( xTimeInMs ) * ( TickType_t ) configTICK_RATE_HZ ) / ( TickType_t ) 1000 ) ) 42 | #endif 43 | 44 | #define pdFALSE ( ( BaseType_t ) 0 ) 45 | #define pdTRUE ( ( BaseType_t ) 1 ) 46 | 47 | #define pdPASS ( pdTRUE ) 48 | #define pdFAIL ( pdFALSE ) 49 | #define errQUEUE_EMPTY ( ( BaseType_t ) 0 ) 50 | #define errQUEUE_FULL ( ( BaseType_t ) 0 ) 51 | 52 | /* FreeRTOS error definitions. */ 53 | #define errCOULD_NOT_ALLOCATE_REQUIRED_MEMORY ( -1 ) 54 | #define errQUEUE_BLOCKED ( -4 ) 55 | #define errQUEUE_YIELD ( -5 ) 56 | 57 | /* Macros used for basic data corruption checks. */ 58 | #ifndef configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 59 | #define configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES 0 60 | #endif 61 | 62 | #if( configUSE_16_BIT_TICKS == 1 ) 63 | #define pdINTEGRITY_CHECK_VALUE 0x5a5a 64 | #else 65 | #define pdINTEGRITY_CHECK_VALUE 0x5a5a5a5aUL 66 | #endif 67 | 68 | /* The following errno values are used by FreeRTOS+ components, not FreeRTOS 69 | itself. */ 70 | #define pdFREERTOS_ERRNO_NONE 0 /* No errors */ 71 | #define pdFREERTOS_ERRNO_ENOENT 2 /* No such file or directory */ 72 | #define pdFREERTOS_ERRNO_EINTR 4 /* Interrupted system call */ 73 | #define pdFREERTOS_ERRNO_EIO 5 /* I/O error */ 74 | #define pdFREERTOS_ERRNO_ENXIO 6 /* No such device or address */ 75 | #define pdFREERTOS_ERRNO_EBADF 9 /* Bad file number */ 76 | #define pdFREERTOS_ERRNO_EAGAIN 11 /* No more processes */ 77 | #define pdFREERTOS_ERRNO_EWOULDBLOCK 11 /* Operation would block */ 78 | #define pdFREERTOS_ERRNO_ENOMEM 12 /* Not enough memory */ 79 | #define pdFREERTOS_ERRNO_EACCES 13 /* Permission denied */ 80 | #define pdFREERTOS_ERRNO_EFAULT 14 /* Bad address */ 81 | #define pdFREERTOS_ERRNO_EBUSY 16 /* Mount device busy */ 82 | #define pdFREERTOS_ERRNO_EEXIST 17 /* File exists */ 83 | #define pdFREERTOS_ERRNO_EXDEV 18 /* Cross-device link */ 84 | #define pdFREERTOS_ERRNO_ENODEV 19 /* No such device */ 85 | #define pdFREERTOS_ERRNO_ENOTDIR 20 /* Not a directory */ 86 | #define pdFREERTOS_ERRNO_EISDIR 21 /* Is a directory */ 87 | #define pdFREERTOS_ERRNO_EINVAL 22 /* Invalid argument */ 88 | #define pdFREERTOS_ERRNO_ENOSPC 28 /* No space left on device */ 89 | #define pdFREERTOS_ERRNO_ESPIPE 29 /* Illegal seek */ 90 | #define pdFREERTOS_ERRNO_EROFS 30 /* Read only file system */ 91 | #define pdFREERTOS_ERRNO_EUNATCH 42 /* Protocol driver not attached */ 92 | #define pdFREERTOS_ERRNO_EBADE 50 /* Invalid exchange */ 93 | #define pdFREERTOS_ERRNO_EFTYPE 79 /* Inappropriate file type or format */ 94 | #define pdFREERTOS_ERRNO_ENMFILE 89 /* No more files */ 95 | #define pdFREERTOS_ERRNO_ENOTEMPTY 90 /* Directory not empty */ 96 | #define pdFREERTOS_ERRNO_ENAMETOOLONG 91 /* File or path name too long */ 97 | #define pdFREERTOS_ERRNO_EOPNOTSUPP 95 /* Operation not supported on transport endpoint */ 98 | #define pdFREERTOS_ERRNO_ENOBUFS 105 /* No buffer space available */ 99 | #define pdFREERTOS_ERRNO_ENOPROTOOPT 109 /* Protocol not available */ 100 | #define pdFREERTOS_ERRNO_EADDRINUSE 112 /* Address already in use */ 101 | #define pdFREERTOS_ERRNO_ETIMEDOUT 116 /* Connection timed out */ 102 | #define pdFREERTOS_ERRNO_EINPROGRESS 119 /* Connection already in progress */ 103 | #define pdFREERTOS_ERRNO_EALREADY 120 /* Socket already connected */ 104 | #define pdFREERTOS_ERRNO_EADDRNOTAVAIL 125 /* Address not available */ 105 | #define pdFREERTOS_ERRNO_EISCONN 127 /* Socket is already connected */ 106 | #define pdFREERTOS_ERRNO_ENOTCONN 128 /* Socket is not connected */ 107 | #define pdFREERTOS_ERRNO_ENOMEDIUM 135 /* No medium inserted */ 108 | #define pdFREERTOS_ERRNO_EILSEQ 138 /* An invalid UTF-16 sequence was encountered. */ 109 | #define pdFREERTOS_ERRNO_ECANCELED 140 /* Operation canceled. */ 110 | 111 | /* The following endian values are used by FreeRTOS+ components, not FreeRTOS 112 | itself. */ 113 | #define pdFREERTOS_LITTLE_ENDIAN 0 114 | #define pdFREERTOS_BIG_ENDIAN 1 115 | 116 | /* Re-defining endian values for generic naming. */ 117 | #define pdLITTLE_ENDIAN pdFREERTOS_LITTLE_ENDIAN 118 | #define pdBIG_ENDIAN pdFREERTOS_BIG_ENDIAN 119 | 120 | 121 | #endif /* PROJDEFS_H */ 122 | 123 | 124 | 125 | -------------------------------------------------------------------------------- /Core/Inc/FreeRTOSConfig.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /* 3 | * FreeRTOS Kernel V10.0.1 4 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 5 | * 6 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 7 | * this software and associated documentation files (the "Software"), to deal in 8 | * the Software without restriction, including without limitation the rights to 9 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 10 | * the Software, and to permit persons to whom the Software is furnished to do so, 11 | * subject to the following conditions: 12 | * 13 | * The above copyright notice and this permission notice shall be included in all 14 | * copies or substantial portions of the Software. 15 | * 16 | * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 17 | * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 18 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 19 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 20 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 21 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 22 | * 23 | * http://www.FreeRTOS.org 24 | * http://aws.amazon.com/freertos 25 | * 26 | * 1 tab == 4 spaces! 27 | */ 28 | /* USER CODE END Header */ 29 | 30 | #ifndef FREERTOS_CONFIG_H 31 | #define FREERTOS_CONFIG_H 32 | 33 | /*----------------------------------------------------------- 34 | * Application specific definitions. 35 | * 36 | * These definitions should be adjusted for your particular hardware and 37 | * application requirements. 38 | * 39 | * These parameters and more are described within the 'configuration' section of the 40 | * FreeRTOS API documentation available on the FreeRTOS.org web site. 41 | * 42 | * See http://www.freertos.org/a00110.html 43 | *----------------------------------------------------------*/ 44 | 45 | /* USER CODE BEGIN Includes */ 46 | /* Section where include file can be added */ 47 | /* USER CODE END Includes */ 48 | 49 | /* Ensure definitions are only used by the compiler, and not by the assembler. */ 50 | #if defined(__ICCARM__) || defined(__CC_ARM) || defined(__GNUC__) 51 | #include 52 | extern uint32_t SystemCoreClock; 53 | #endif 54 | #define configUSE_PREEMPTION 1 55 | #define configSUPPORT_STATIC_ALLOCATION 1 56 | #define configSUPPORT_DYNAMIC_ALLOCATION 1 57 | #define configUSE_IDLE_HOOK 0 58 | #define configUSE_TICK_HOOK 0 59 | #define configCPU_CLOCK_HZ ( SystemCoreClock ) 60 | #define configTICK_RATE_HZ ((TickType_t)1000) 61 | #define configMAX_PRIORITIES ( 7 ) 62 | #define configMINIMAL_STACK_SIZE ((uint16_t)64) 63 | #define configTOTAL_HEAP_SIZE ((size_t)12000) 64 | #define configMAX_TASK_NAME_LEN ( 16 ) 65 | #define configUSE_16_BIT_TICKS 0 66 | #define configUSE_MUTEXES 1 67 | #define configQUEUE_REGISTRY_SIZE 8 68 | #define configUSE_PORT_OPTIMISED_TASK_SELECTION 1 69 | 70 | /* Co-routine definitions. */ 71 | #define configUSE_CO_ROUTINES 0 72 | #define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) 73 | 74 | /* The following flag must be enabled only when using newlib */ 75 | #define configUSE_NEWLIB_REENTRANT 1 76 | 77 | /* Set the following definitions to 1 to include the API function, or zero 78 | to exclude the API function. */ 79 | #define INCLUDE_vTaskPrioritySet 1 80 | #define INCLUDE_uxTaskPriorityGet 1 81 | #define INCLUDE_vTaskDelete 1 82 | #define INCLUDE_vTaskCleanUpResources 0 83 | #define INCLUDE_vTaskSuspend 1 84 | #define INCLUDE_vTaskDelayUntil 1 85 | #define INCLUDE_vTaskDelay 1 86 | #define INCLUDE_xTaskGetSchedulerState 1 87 | 88 | /* Cortex-M specific definitions. */ 89 | #ifdef __NVIC_PRIO_BITS 90 | /* __BVIC_PRIO_BITS will be specified when CMSIS is being used. */ 91 | #define configPRIO_BITS __NVIC_PRIO_BITS 92 | #else 93 | #define configPRIO_BITS 4 94 | #endif 95 | 96 | /* The lowest interrupt priority that can be used in a call to a "set priority" 97 | function. */ 98 | #define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15 99 | 100 | /* The highest interrupt priority that can be used by any interrupt service 101 | routine that makes calls to interrupt safe FreeRTOS API functions. DO NOT CALL 102 | INTERRUPT SAFE FREERTOS API FUNCTIONS FROM ANY INTERRUPT THAT HAS A HIGHER 103 | PRIORITY THAN THIS! (higher priorities are lower numeric values. */ 104 | #define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5 105 | 106 | /* Interrupt priorities used by the kernel port layer itself. These are generic 107 | to all Cortex-M ports, and do not rely on any particular library functions. */ 108 | #define configKERNEL_INTERRUPT_PRIORITY ( configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) 109 | /* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!! 110 | See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */ 111 | #define configMAX_SYSCALL_INTERRUPT_PRIORITY ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) ) 112 | 113 | /* Normal assert() semantics without relying on the provision of an assert.h 114 | header file. */ 115 | /* USER CODE BEGIN 1 */ 116 | #define configASSERT( x ) if ((x) == 0) {taskDISABLE_INTERRUPTS(); for( ;; );} 117 | /* USER CODE END 1 */ 118 | 119 | /* Definitions that map the FreeRTOS port interrupt handlers to their CMSIS 120 | standard names. */ 121 | #define vPortSVCHandler SVC_Handler 122 | #define xPortPendSVHandler PendSV_Handler 123 | 124 | /* IMPORTANT: This define is commented when used with STM32Cube firmware, when the timebase source is SysTick, 125 | to prevent overwriting SysTick_Handler defined within STM32Cube HAL */ 126 | 127 | #define xPortSysTickHandler SysTick_Handler 128 | 129 | /* USER CODE BEGIN Defines */ 130 | /* Section where parameter definitions can be added (for instance, to override default ones in FreeRTOS.h) */ 131 | /* USER CODE END Defines */ 132 | 133 | #endif /* FREERTOS_CONFIG_H */ 134 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/stack_macros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef STACK_MACROS_H 29 | #define STACK_MACROS_H 30 | 31 | /* 32 | * Call the stack overflow hook function if the stack of the task being swapped 33 | * out is currently overflowed, or looks like it might have overflowed in the 34 | * past. 35 | * 36 | * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check 37 | * the current stack state only - comparing the current top of stack value to 38 | * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 39 | * will also cause the last few stack bytes to be checked to ensure the value 40 | * to which the bytes were set when the task was created have not been 41 | * overwritten. Note this second test does not guarantee that an overflowed 42 | * stack will always be recognised. 43 | */ 44 | 45 | /*-----------------------------------------------------------*/ 46 | 47 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) 48 | 49 | /* Only the current stack state is to be checked. */ 50 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 51 | { \ 52 | /* Is the currently saved stack pointer within the stack limit? */ \ 53 | if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ 54 | { \ 55 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 56 | } \ 57 | } 58 | 59 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 60 | /*-----------------------------------------------------------*/ 61 | 62 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) 63 | 64 | /* Only the current stack state is to be checked. */ 65 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 66 | { \ 67 | \ 68 | /* Is the currently saved stack pointer within the stack limit? */ \ 69 | if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ 70 | { \ 71 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 72 | } \ 73 | } 74 | 75 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 76 | /*-----------------------------------------------------------*/ 77 | 78 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) 79 | 80 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 81 | { \ 82 | const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ 83 | const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ 84 | \ 85 | if( ( pulStack[ 0 ] != ulCheckValue ) || \ 86 | ( pulStack[ 1 ] != ulCheckValue ) || \ 87 | ( pulStack[ 2 ] != ulCheckValue ) || \ 88 | ( pulStack[ 3 ] != ulCheckValue ) ) \ 89 | { \ 90 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 91 | } \ 92 | } 93 | 94 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 95 | /*-----------------------------------------------------------*/ 96 | 97 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) 98 | 99 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 100 | { \ 101 | int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ 102 | static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 103 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 104 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 105 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 106 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ 107 | \ 108 | \ 109 | pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ 110 | \ 111 | /* Has the extremity of the task stack ever been written over? */ \ 112 | if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ 113 | { \ 114 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 115 | } \ 116 | } 117 | 118 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 119 | /*-----------------------------------------------------------*/ 120 | 121 | /* Remove stack overflow macro if not being used. */ 122 | #ifndef taskCHECK_FOR_STACK_OVERFLOW 123 | #define taskCHECK_FOR_STACK_OVERFLOW() 124 | #endif 125 | 126 | 127 | 128 | #endif /* STACK_MACROS_H */ 129 | 130 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/StackMacros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef STACK_MACROS_H 29 | #define STACK_MACROS_H 30 | 31 | #ifndef _MSC_VER /* Visual Studio doesn't support #warning. */ 32 | #warning The name of this file has changed to stack_macros.h. Please update your code accordingly. This source file (which has the original name) will be removed in future released. 33 | #endif 34 | 35 | /* 36 | * Call the stack overflow hook function if the stack of the task being swapped 37 | * out is currently overflowed, or looks like it might have overflowed in the 38 | * past. 39 | * 40 | * Setting configCHECK_FOR_STACK_OVERFLOW to 1 will cause the macro to check 41 | * the current stack state only - comparing the current top of stack value to 42 | * the stack limit. Setting configCHECK_FOR_STACK_OVERFLOW to greater than 1 43 | * will also cause the last few stack bytes to be checked to ensure the value 44 | * to which the bytes were set when the task was created have not been 45 | * overwritten. Note this second test does not guarantee that an overflowed 46 | * stack will always be recognised. 47 | */ 48 | 49 | /*-----------------------------------------------------------*/ 50 | 51 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH < 0 ) ) 52 | 53 | /* Only the current stack state is to be checked. */ 54 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 55 | { \ 56 | /* Is the currently saved stack pointer within the stack limit? */ \ 57 | if( pxCurrentTCB->pxTopOfStack <= pxCurrentTCB->pxStack ) \ 58 | { \ 59 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 60 | } \ 61 | } 62 | 63 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 64 | /*-----------------------------------------------------------*/ 65 | 66 | #if( ( configCHECK_FOR_STACK_OVERFLOW == 1 ) && ( portSTACK_GROWTH > 0 ) ) 67 | 68 | /* Only the current stack state is to be checked. */ 69 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 70 | { \ 71 | \ 72 | /* Is the currently saved stack pointer within the stack limit? */ \ 73 | if( pxCurrentTCB->pxTopOfStack >= pxCurrentTCB->pxEndOfStack ) \ 74 | { \ 75 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 76 | } \ 77 | } 78 | 79 | #endif /* configCHECK_FOR_STACK_OVERFLOW == 1 */ 80 | /*-----------------------------------------------------------*/ 81 | 82 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH < 0 ) ) 83 | 84 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 85 | { \ 86 | const uint32_t * const pulStack = ( uint32_t * ) pxCurrentTCB->pxStack; \ 87 | const uint32_t ulCheckValue = ( uint32_t ) 0xa5a5a5a5; \ 88 | \ 89 | if( ( pulStack[ 0 ] != ulCheckValue ) || \ 90 | ( pulStack[ 1 ] != ulCheckValue ) || \ 91 | ( pulStack[ 2 ] != ulCheckValue ) || \ 92 | ( pulStack[ 3 ] != ulCheckValue ) ) \ 93 | { \ 94 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 95 | } \ 96 | } 97 | 98 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 99 | /*-----------------------------------------------------------*/ 100 | 101 | #if( ( configCHECK_FOR_STACK_OVERFLOW > 1 ) && ( portSTACK_GROWTH > 0 ) ) 102 | 103 | #define taskCHECK_FOR_STACK_OVERFLOW() \ 104 | { \ 105 | int8_t *pcEndOfStack = ( int8_t * ) pxCurrentTCB->pxEndOfStack; \ 106 | static const uint8_t ucExpectedStackBytes[] = { tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 107 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 108 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 109 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, \ 110 | tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE, tskSTACK_FILL_BYTE }; \ 111 | \ 112 | \ 113 | pcEndOfStack -= sizeof( ucExpectedStackBytes ); \ 114 | \ 115 | /* Has the extremity of the task stack ever been written over? */ \ 116 | if( memcmp( ( void * ) pcEndOfStack, ( void * ) ucExpectedStackBytes, sizeof( ucExpectedStackBytes ) ) != 0 ) \ 117 | { \ 118 | vApplicationStackOverflowHook( ( TaskHandle_t ) pxCurrentTCB, pxCurrentTCB->pcTaskName ); \ 119 | } \ 120 | } 121 | 122 | #endif /* #if( configCHECK_FOR_STACK_OVERFLOW > 1 ) */ 123 | /*-----------------------------------------------------------*/ 124 | 125 | /* Remove stack overflow macro if not being used. */ 126 | #ifndef taskCHECK_FOR_STACK_OVERFLOW 127 | #define taskCHECK_FOR_STACK_OVERFLOW() 128 | #endif 129 | 130 | 131 | 132 | #endif /* STACK_MACROS_H */ 133 | 134 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/portable.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | /*----------------------------------------------------------- 29 | * Portable layer API. Each function must be defined for each port. 30 | *----------------------------------------------------------*/ 31 | 32 | #ifndef PORTABLE_H 33 | #define PORTABLE_H 34 | 35 | /* Each FreeRTOS port has a unique portmacro.h header file. Originally a 36 | pre-processor definition was used to ensure the pre-processor found the correct 37 | portmacro.h file for the port being used. That scheme was deprecated in favour 38 | of setting the compiler's include path such that it found the correct 39 | portmacro.h file - removing the need for the constant and allowing the 40 | portmacro.h file to be located anywhere in relation to the port being used. 41 | Purely for reasons of backward compatibility the old method is still valid, but 42 | to make it clear that new projects should not use it, support for the port 43 | specific constants has been moved into the deprecated_definitions.h header 44 | file. */ 45 | #include "deprecated_definitions.h" 46 | 47 | /* If portENTER_CRITICAL is not defined then including deprecated_definitions.h 48 | did not result in a portmacro.h header file being included - and it should be 49 | included here. In this case the path to the correct portmacro.h header file 50 | must be set in the compiler's include path. */ 51 | #ifndef portENTER_CRITICAL 52 | #include "portmacro.h" 53 | #endif 54 | 55 | #if portBYTE_ALIGNMENT == 32 56 | #define portBYTE_ALIGNMENT_MASK ( 0x001f ) 57 | #endif 58 | 59 | #if portBYTE_ALIGNMENT == 16 60 | #define portBYTE_ALIGNMENT_MASK ( 0x000f ) 61 | #endif 62 | 63 | #if portBYTE_ALIGNMENT == 8 64 | #define portBYTE_ALIGNMENT_MASK ( 0x0007 ) 65 | #endif 66 | 67 | #if portBYTE_ALIGNMENT == 4 68 | #define portBYTE_ALIGNMENT_MASK ( 0x0003 ) 69 | #endif 70 | 71 | #if portBYTE_ALIGNMENT == 2 72 | #define portBYTE_ALIGNMENT_MASK ( 0x0001 ) 73 | #endif 74 | 75 | #if portBYTE_ALIGNMENT == 1 76 | #define portBYTE_ALIGNMENT_MASK ( 0x0000 ) 77 | #endif 78 | 79 | #ifndef portBYTE_ALIGNMENT_MASK 80 | #error "Invalid portBYTE_ALIGNMENT definition" 81 | #endif 82 | 83 | #ifndef portNUM_CONFIGURABLE_REGIONS 84 | #define portNUM_CONFIGURABLE_REGIONS 1 85 | #endif 86 | 87 | #ifdef __cplusplus 88 | extern "C" { 89 | #endif 90 | 91 | #include "mpu_wrappers.h" 92 | 93 | /* 94 | * Setup the stack of a new task so it is ready to be placed under the 95 | * scheduler control. The registers have to be placed on the stack in 96 | * the order that the port expects to find them. 97 | * 98 | */ 99 | #if( portUSING_MPU_WRAPPERS == 1 ) 100 | StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters, BaseType_t xRunPrivileged ) PRIVILEGED_FUNCTION; 101 | #else 102 | StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters ) PRIVILEGED_FUNCTION; 103 | #endif 104 | 105 | /* Used by heap_5.c. */ 106 | typedef struct HeapRegion 107 | { 108 | uint8_t *pucStartAddress; 109 | size_t xSizeInBytes; 110 | } HeapRegion_t; 111 | 112 | /* 113 | * Used to define multiple heap regions for use by heap_5.c. This function 114 | * must be called before any calls to pvPortMalloc() - not creating a task, 115 | * queue, semaphore, mutex, software timer, event group, etc. will result in 116 | * pvPortMalloc being called. 117 | * 118 | * pxHeapRegions passes in an array of HeapRegion_t structures - each of which 119 | * defines a region of memory that can be used as the heap. The array is 120 | * terminated by a HeapRegions_t structure that has a size of 0. The region 121 | * with the lowest start address must appear first in the array. 122 | */ 123 | void vPortDefineHeapRegions( const HeapRegion_t * const pxHeapRegions ) PRIVILEGED_FUNCTION; 124 | 125 | 126 | /* 127 | * Map to the memory management routines required for the port. 128 | */ 129 | void *pvPortMalloc( size_t xSize ) PRIVILEGED_FUNCTION; 130 | void vPortFree( void *pv ) PRIVILEGED_FUNCTION; 131 | void vPortInitialiseBlocks( void ) PRIVILEGED_FUNCTION; 132 | size_t xPortGetFreeHeapSize( void ) PRIVILEGED_FUNCTION; 133 | size_t xPortGetMinimumEverFreeHeapSize( void ) PRIVILEGED_FUNCTION; 134 | 135 | /* 136 | * Setup the hardware ready for the scheduler to take control. This generally 137 | * sets up a tick interrupt and sets timers for the correct tick frequency. 138 | */ 139 | BaseType_t xPortStartScheduler( void ) PRIVILEGED_FUNCTION; 140 | 141 | /* 142 | * Undo any hardware/ISR setup that was performed by xPortStartScheduler() so 143 | * the hardware is left in its original condition after the scheduler stops 144 | * executing. 145 | */ 146 | void vPortEndScheduler( void ) PRIVILEGED_FUNCTION; 147 | 148 | /* 149 | * The structures and methods of manipulating the MPU are contained within the 150 | * port layer. 151 | * 152 | * Fills the xMPUSettings structure with the memory region information 153 | * contained in xRegions. 154 | */ 155 | #if( portUSING_MPU_WRAPPERS == 1 ) 156 | struct xMEMORY_REGION; 157 | void vPortStoreTaskMPUSettings( xMPU_SETTINGS *xMPUSettings, const struct xMEMORY_REGION * const xRegions, StackType_t *pxBottomOfStack, uint32_t ulStackDepth ) PRIVILEGED_FUNCTION; 158 | #endif 159 | 160 | #ifdef __cplusplus 161 | } 162 | #endif 163 | 164 | #endif /* PORTABLE_H */ 165 | 166 | -------------------------------------------------------------------------------- /GUI/gui.c: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "gui.h" 4 | #include "image.h" 5 | #include "FOC_utils.h" 6 | 7 | 8 | const char foc_mode_name[FOC_CONTROL_MODE_NUM][20] = { 9 | "OPEN POS", 10 | "OPEN VEL", 11 | "TORQUE", 12 | "VELOCITY", 13 | "POSITION", 14 | "SPRING", 15 | "SPRING DMP", 16 | "DAMP", 17 | "KNOB", 18 | "0 RESIST" 19 | }; 20 | 21 | 22 | void gui_draw_line(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t color) { 23 | if (x1 == x2) { // slope == infinite 24 | if (y2 < y1) { // Make sure that y1 <= y2 25 | uint8_t temp = y2; 26 | y2 = y1; 27 | y1 = temp; 28 | } 29 | for (uint8_t y0 = y1; y0 <= y2; y0++) { 30 | ST7735_DrawPixel(x1, y0, color); 31 | } 32 | return; 33 | } 34 | 35 | if (x2 < x1) { // Make sure that x1 <= x2 36 | // Swap two variable in-place 37 | uint8_t temp = x2; 38 | x2 = x1; 39 | x1 = temp; 40 | 41 | temp = y2; 42 | y2 = y1; 43 | y1 = temp; 44 | } 45 | 46 | 47 | for (uint8_t x0 = x1; x0 <= x2; x0++) { // iterate each pixel of the line 48 | uint8_t y0 = (y2 - y1) * (x0 - x1) / (x2 - x1) + y1; 49 | ST7735_DrawPixel(x0, y0, color); 50 | } 51 | return; 52 | } 53 | 54 | void gui_draw_rectangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint8_t fill, uint16_t color) { 55 | // Clock wise from left top 56 | if (fill) { 57 | for (int i = y1; i <= y2; i++) { 58 | for (int j = x1; j <= x2; j++) { 59 | ST7735_DrawPixel(j, i, color); 60 | } 61 | } 62 | return; 63 | } 64 | 65 | gui_draw_line(x1, y1, x2, y1, color); // Line1 66 | gui_draw_line(x2, y1, x2, y2, color); // Line2 67 | gui_draw_line(x2, y2, x1, y2, color); // Line3 68 | gui_draw_line(x1, y2, x1, y1, color); // Line4 69 | return; 70 | } 71 | 72 | void gui_draw_triangle(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, uint16_t x3, uint16_t y3, uint16_t color) { 73 | // Clock wise from left top 74 | 75 | gui_draw_line(x1, y1, x2, y2, color); // Line1 76 | gui_draw_line(x2, y2, x3, y3, color); // Line2 77 | gui_draw_line(x3, y3, x1, y1, color); // Line3 78 | } 79 | 80 | void gui_draw_init(const char *init_info, uint8_t refresh) { 81 | static const int delay_time = 200; 82 | 83 | if (refresh) { 84 | ST7735_FillScreen(BACKGROUND_COLOR); 85 | ST7735_DrawImage(0, 0, ST7735_HEIGHT, ST7735_HEIGHT, (uint16_t *) head_portrait_80x80); 86 | 87 | ST7735_WriteString(80, 20, "FOC", Font_11x18, TITLE_COLOR, BACKGROUND_COLOR); 88 | ST7735_WriteString(80, 38, "Driver", Font_11x18, TITLE_COLOR, BACKGROUND_COLOR); 89 | gui_draw_line(80, 18, 150, 18, TEXT_COLOR); 90 | gui_draw_line(80, 68, 150, 68, TEXT_COLOR); 91 | 92 | ST7735_WriteString(80, 56, init_info, Font_7x10, TEXT_COLOR, BACKGROUND_COLOR); 93 | } else { 94 | ST7735_FillRectangle(80, 56, 80, 10, BACKGROUND_COLOR); 95 | ST7735_WriteString(80, 56, init_info, Font_7x10, TEXT_COLOR, BACKGROUND_COLOR); 96 | } 97 | } 98 | 99 | void gui_draw_mode_selection(FOC_CONTROL_MODE mode) { 100 | 101 | static const int y = 65, width = 23, height = 12; 102 | ST7735_FillScreenFast(BACKGROUND_COLOR); 103 | 104 | gui_draw_line(0, y - 3, 180, y - 3, TEXT_COLOR); 105 | gui_draw_line(0, 20, 180, 20, TEXT_COLOR); 106 | 107 | gui_draw_button(10, y, width, height, "lef", TEXT_COLOR, BACKGROUND_COLOR); 108 | gui_draw_button(50, y, width, height, "cfm", TEXT_COLOR, BACKGROUND_COLOR); 109 | // gui_draw_button(90, y, width, height, "cel", ST7735_BLACK, ST7735_WHITE); 110 | gui_draw_button(130, y, width, height, "rig", TEXT_COLOR, BACKGROUND_COLOR); 111 | 112 | ST7735_WriteString(0, 0, "Mode Selection", Font_11x18, TEXT_COLOR, BACKGROUND_COLOR); 113 | 114 | 115 | ST7735_WriteString(0, 30, foc_mode_name[mode], Font_16x26, TITLE_COLOR, BACKGROUND_COLOR); 116 | 117 | ST7735_FillRectangle(0, 57, ST7735_WIDTH * (mode + 1) / FOC_CONTROL_MODE_NUM, 3, BAR_COLOR); 118 | 119 | // gui_draw_parameter(0, 57, "A", 10); 120 | } 121 | 122 | void gui_draw_position_mode(float angle, uint8_t refresh) { 123 | static const int y = 65, width = 23, height = 12; 124 | if (refresh) { 125 | ST7735_FillScreenFast(BACKGROUND_COLOR); 126 | 127 | gui_draw_line(0, y - 3, 180, y - 3, TEXT_COLOR); 128 | gui_draw_line(0, 20, 180, 20, TEXT_COLOR); 129 | 130 | gui_draw_button(10, y, width, height, "lef", TEXT_COLOR, BACKGROUND_COLOR); 131 | // gui_draw_button(50, y, width, height, "cfm", ST7735_BLACK, ST7735_WHITE); 132 | gui_draw_button(90, y, width, height, "cel", TEXT_COLOR, BACKGROUND_COLOR); 133 | gui_draw_button(130, y, width, height, "rig", TEXT_COLOR, BACKGROUND_COLOR); 134 | 135 | ST7735_WriteString(0, 0, "Position Mode", Font_11x18, TITLE_COLOR, BACKGROUND_COLOR); 136 | } else { 137 | ST7735_FillRectangle(0, 21, 180, 40, BACKGROUND_COLOR); 138 | } 139 | // show parameters 140 | gui_draw_parameter(0, 22, "Angle", angle * _RADIAN_TO_DEGREE, 0, 0); 141 | } 142 | 143 | void 144 | gui_draw_button(uint16_t x, uint16_t y, uint16_t w, uint16_t h, const char *string, uint16_t color, uint16_t bgcolor) { 145 | 146 | gui_draw_line(x, y, x + w, y, color); 147 | gui_draw_line(x + w, y, x + w, y + h, color); 148 | gui_draw_line(x + w, y + h, x, y + h, color); 149 | gui_draw_line(x, y + h, x, y, color); 150 | ST7735_WriteString(x + 1, y + 1, string, Font_7x10, color, bgcolor); 151 | } 152 | 153 | void gui_draw_parameter(uint16_t x, uint16_t y, const char *item, int16_t value, uint8_t change, uint8_t selected) { 154 | char data[20], num[10]; 155 | strcpy(data, item); 156 | strcat(data, ":"); 157 | itoa(value, num, 10); 158 | strcat(data, num); 159 | if (selected) { 160 | if (change) { 161 | ST7735_WriteString(x, y, data, Font_7x10, TEXT_COLOR, SELECTED_COLOR); 162 | } else { 163 | ST7735_WriteString(x, y, data, Font_7x10, BACKGROUND_COLOR, SELECTED_COLOR); 164 | } 165 | } else { 166 | ST7735_WriteString(x, y, data, Font_7x10, TEXT_COLOR, BACKGROUND_COLOR); 167 | } 168 | } 169 | 170 | void gui_draw_knob_mode(uint8_t sector_num, uint8_t k, uint8_t max_force, uint8_t select_param, uint8_t change, 171 | uint8_t refresh) { 172 | static const int y = 65, width = 23, height = 12; 173 | static const char param_name[3][10] = { 174 | "Sector", 175 | "k", 176 | "max_F", 177 | }; 178 | static uint8_t values[3]; 179 | 180 | if (refresh) { 181 | ST7735_FillScreenFast(BACKGROUND_COLOR); 182 | 183 | gui_draw_line(0, y - 3, 180, y - 3, TEXT_COLOR); 184 | gui_draw_line(0, 20, 180, 20, TEXT_COLOR); 185 | 186 | gui_draw_button(10, y, width, height, "lef", TEXT_COLOR, BACKGROUND_COLOR); 187 | // gui_draw_button(50, y, width, height, "cfm", ST7735_BLACK, ST7735_WHITE); 188 | gui_draw_button(90, y, width, height, "cel", TEXT_COLOR, BACKGROUND_COLOR); 189 | gui_draw_button(130, y, width, height, "rig", TEXT_COLOR, BACKGROUND_COLOR); 190 | 191 | ST7735_WriteString(0, 0, "Knob Mode", Font_11x18, TITLE_COLOR, BACKGROUND_COLOR); 192 | } else { 193 | ST7735_FillRectangle(0, 21, 180, 40, BACKGROUND_COLOR); 194 | } 195 | 196 | // show parameters 197 | values[0] = sector_num, values[1] = k, values[2] = max_force; 198 | for (int i = 0; i < 3; ++i) { 199 | if (select_param == i + 1) { 200 | gui_draw_parameter(0, 22 + i * 10, param_name[i], values[i], change, 1); 201 | } else { 202 | gui_draw_parameter(0, 22 + i * 10, param_name[i], values[i], change, 0); 203 | } 204 | } 205 | } 206 | 207 | 208 | 209 | 210 | -------------------------------------------------------------------------------- /GUI/st7735/st7735.h: -------------------------------------------------------------------------------- 1 | /* vim: set ai et ts=4 sw=4: */ 2 | #ifndef __ST7735_H__ 3 | #define __ST7735_H__ 4 | 5 | #include "fonts.h" 6 | #include 7 | #include "spi.h" 8 | 9 | #define ST7735_MADCTL_MY 0x80 10 | #define ST7735_MADCTL_MX 0x40 11 | #define ST7735_MADCTL_MV 0x20 12 | #define ST7735_MADCTL_ML 0x10 13 | #define ST7735_MADCTL_RGB 0x00 14 | #define ST7735_MADCTL_BGR 0x08 15 | #define ST7735_MADCTL_MH 0x04 16 | 17 | /*** Redefine if necessary ***/ 18 | #define ST7735_SPI_PORT hspi1 19 | extern SPI_HandleTypeDef ST7735_SPI_PORT; 20 | 21 | #define ST7735_RES_Pin GPIO_PIN_6 22 | #define ST7735_RES_GPIO_Port GPIOA 23 | //#define ST7735_CS_Pin GPIO_PIN_6 24 | //#define ST7735_CS_GPIO_Port GPIOB 25 | #define ST7735_DC_Pin GPIO_PIN_4 26 | #define ST7735_DC_GPIO_Port GPIOA 27 | 28 | // AliExpress/eBay 1.8" display, default orientation 29 | /* 30 | #define ST7735_IS_160X128 1 31 | #define ST7735_WIDTH 128 32 | #define ST7735_HEIGHT 160 33 | #define ST7735_XSTART 0 34 | #define ST7735_YSTART 0 35 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MY) 36 | */ 37 | 38 | // AliExpress/eBay 1.8" display, rotate right 39 | /* 40 | #define ST7735_IS_160X128 1 41 | #define ST7735_WIDTH 160 42 | #define ST7735_HEIGHT 128 43 | #define ST7735_XSTART 0 44 | #define ST7735_YSTART 0 45 | #define ST7735_ROTATION (ST7735_MADCTL_MY | ST7735_MADCTL_MV) 46 | */ 47 | 48 | // AliExpress/eBay 1.8" display, rotate left 49 | /* 50 | #define ST7735_IS_160X128 1 51 | #define ST7735_WIDTH 160 52 | #define ST7735_HEIGHT 128 53 | #define ST7735_XSTART 0 54 | #define ST7735_YSTART 0 55 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MV) 56 | */ 57 | 58 | // AliExpress/eBay 1.8" display, upside down 59 | /* 60 | #define ST7735_IS_160X128 1 61 | #define ST7735_WIDTH 128 62 | #define ST7735_HEIGHT 160 63 | #define ST7735_XSTART 0 64 | #define ST7735_YSTART 0 65 | #define ST7735_ROTATION (0) 66 | */ 67 | 68 | // WaveShare ST7735S-based 1.8" display, default orientation 69 | /* 70 | #define ST7735_IS_160X128 1 71 | #define ST7735_WIDTH 128 72 | #define ST7735_HEIGHT 160 73 | #define ST7735_XSTART 2 74 | #define ST7735_YSTART 1 75 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MY | ST7735_MADCTL_RGB) 76 | */ 77 | 78 | // WaveShare ST7735S-based 1.8" display, rotate right 79 | /* 80 | #define ST7735_IS_160X128 1 81 | #define ST7735_WIDTH 160 82 | #define ST7735_HEIGHT 128 83 | #define ST7735_XSTART 1 84 | #define ST7735_YSTART 2 85 | #define ST7735_ROTATION (ST7735_MADCTL_MY | ST7735_MADCTL_MV | ST7735_MADCTL_RGB) 86 | */ 87 | 88 | // WaveShare ST7735S-based 1.8" display, rotate left 89 | /* 90 | #define ST7735_IS_160X128 1 91 | #define ST7735_WIDTH 160 92 | #define ST7735_HEIGHT 128 93 | #define ST7735_XSTART 1 94 | #define ST7735_YSTART 2 95 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MV | ST7735_MADCTL_RGB) 96 | */ 97 | 98 | // WaveShare ST7735S-based 1.8" display, upside down 99 | /* 100 | #define ST7735_IS_160X128 1 101 | #define ST7735_WIDTH 128 102 | #define ST7735_HEIGHT 160 103 | #define ST7735_XSTART 2 104 | #define ST7735_YSTART 1 105 | #define ST7735_ROTATION (ST7735_MADCTL_RGB) 106 | */ 107 | 108 | // 1.44" display, default orientation 109 | /* 110 | #define ST7735_IS_128X128 1 111 | #define ST7735_WIDTH 128 112 | #define ST7735_HEIGHT 128 113 | #define ST7735_XSTART 2 114 | #define ST7735_YSTART 3 115 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MY | ST7735_MADCTL_BGR) 116 | */ 117 | 118 | // 1.44" display, rotate right 119 | /* 120 | #define ST7735_IS_128X128 1 121 | #define ST7735_WIDTH 128 122 | #define ST7735_HEIGHT 128 123 | #define ST7735_XSTART 3 124 | #define ST7735_YSTART 2 125 | #define ST7735_ROTATION (ST7735_MADCTL_MY | ST7735_MADCTL_MV | ST7735_MADCTL_BGR) 126 | */ 127 | 128 | // 1.44" display, rotate left 129 | /* 130 | #define ST7735_IS_128X128 1 131 | #define ST7735_WIDTH 128 132 | #define ST7735_HEIGHT 128 133 | #define ST7735_XSTART 1 134 | #define ST7735_YSTART 2 135 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MV | ST7735_MADCTL_BGR) 136 | */ 137 | 138 | // 1.44" display, upside down 139 | /* 140 | #define ST7735_IS_128X128 1 141 | #define ST7735_WIDTH 128 142 | #define ST7735_HEIGHT 128 143 | #define ST7735_XSTART 2 144 | #define ST7735_YSTART 1 145 | #define ST7735_ROTATION (ST7735_MADCTL_BGR) 146 | */ 147 | 148 | // Zhong Jing Yuan 0.96" IPS LCD 80*160 149 | 150 | // mini 160x80 display (it's unlikely you want the default orientation) 151 | 152 | /* 153 | #define ST7735_IS_160X80 1 154 | #define ST7735_XSTART 26 155 | #define ST7735_YSTART 1 156 | #define ST7735_WIDTH 80 157 | #define ST7735_HEIGHT 160 158 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MY | ST7735_MADCTL_BGR) 159 | */ 160 | 161 | // mini 160x80, rotate left 162 | /* 163 | #define ST7735_IS_160X80 1 164 | #define ST7735_XSTART 1 165 | #define ST7735_YSTART 26 166 | #define ST7735_WIDTH 160 167 | #define ST7735_HEIGHT 80 168 | #define ST7735_ROTATION (ST7735_MADCTL_MX | ST7735_MADCTL_MV | ST7735_MADCTL_BGR) 169 | */ 170 | 171 | // mini 160x80, rotate right 172 | 173 | #define ST7735_IS_160X80 1 174 | #define ST7735_XSTART 1 175 | #define ST7735_YSTART 26 176 | #define ST7735_WIDTH 160 177 | #define ST7735_HEIGHT 80 178 | #define ST7735_ROTATION (ST7735_MADCTL_MY | ST7735_MADCTL_MV | ST7735_MADCTL_BGR) 179 | 180 | 181 | /****************************/ 182 | 183 | #define ST7735_NOP 0x00 184 | #define ST7735_SWRESET 0x01 185 | #define ST7735_RDDID 0x04 186 | #define ST7735_RDDST 0x09 187 | 188 | #define ST7735_SLPIN 0x10 189 | #define ST7735_SLPOUT 0x11 190 | #define ST7735_PTLON 0x12 191 | #define ST7735_NORON 0x13 192 | 193 | #define ST7735_INVOFF 0x20 194 | #define ST7735_INVON 0x21 195 | #define ST7735_GAMSET 0x26 196 | #define ST7735_DISPOFF 0x28 197 | #define ST7735_DISPON 0x29 198 | #define ST7735_CASET 0x2A 199 | #define ST7735_RASET 0x2B 200 | #define ST7735_RAMWR 0x2C 201 | #define ST7735_RAMRD 0x2E 202 | 203 | #define ST7735_PTLAR 0x30 204 | #define ST7735_COLMOD 0x3A 205 | #define ST7735_MADCTL 0x36 206 | 207 | #define ST7735_FRMCTR1 0xB1 208 | #define ST7735_FRMCTR2 0xB2 209 | #define ST7735_FRMCTR3 0xB3 210 | #define ST7735_INVCTR 0xB4 211 | #define ST7735_DISSET5 0xB6 212 | 213 | #define ST7735_PWCTR1 0xC0 214 | #define ST7735_PWCTR2 0xC1 215 | #define ST7735_PWCTR3 0xC2 216 | #define ST7735_PWCTR4 0xC3 217 | #define ST7735_PWCTR5 0xC4 218 | #define ST7735_VMCTR1 0xC5 219 | 220 | #define ST7735_RDID1 0xDA 221 | #define ST7735_RDID2 0xDB 222 | #define ST7735_RDID3 0xDC 223 | #define ST7735_RDID4 0xDD 224 | 225 | #define ST7735_PWCTR6 0xFC 226 | 227 | #define ST7735_GMCTRP1 0xE0 228 | #define ST7735_GMCTRN1 0xE1 229 | 230 | // Color definitions 231 | #define ST7735_BLACK 0x0000 232 | #define ST7735_BLUE 0x001F 233 | #define ST7735_RED 0xF800 234 | #define ST7735_GREEN 0x07E0 235 | #define ST7735_CYAN 0x07FF 236 | #define ST7735_MAGENTA 0xF81F 237 | #define ST7735_YELLOW 0xFFE0 238 | #define ST7735_WHITE 0xFFFF 239 | #define ST7735_COLOR565(r, g, b) (((r & 0xF8) << 8) | ((g & 0xFC) << 3) | ((b & 0xF8) >> 3)) 240 | 241 | typedef enum { 242 | GAMMA_10 = 0x01, 243 | GAMMA_25 = 0x02, 244 | GAMMA_22 = 0x04, 245 | GAMMA_18 = 0x08 246 | } GammaDef; 247 | 248 | #ifdef __cplusplus 249 | extern "C" { 250 | #endif 251 | 252 | // call before initializing any SPI devices 253 | void ST7735_Unselect(); 254 | 255 | void ST7735_Init(void); 256 | void ST7735_DrawPixel(uint16_t x, uint16_t y, uint16_t color); 257 | void ST7735_WriteString(uint16_t x, uint16_t y, const char* str, FontDef font, uint16_t color, uint16_t bgcolor); 258 | void ST7735_FillRectangle(uint16_t x, uint16_t y, uint16_t w, uint16_t h, uint16_t color); 259 | void ST7735_FillRectangleFast(uint16_t x, uint16_t y, uint16_t w, uint16_t h, uint16_t color); 260 | void ST7735_FillScreen(uint16_t color); 261 | void ST7735_FillScreenFast(uint16_t color); 262 | void ST7735_DrawImage(uint16_t x, uint16_t y, uint16_t w, uint16_t h, const uint16_t* data); 263 | void ST7735_InvertColors(bool invert); 264 | void ST7735_SetGamma(GammaDef gamma); 265 | 266 | #ifdef __cplusplus 267 | } 268 | #endif 269 | 270 | #endif // __ST7735_H__ 271 | -------------------------------------------------------------------------------- /Drivers/STM32F1xx_HAL_Driver/Inc/stm32f1xx_hal_def.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32f1xx_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 __STM32F1xx_HAL_DEF 23 | #define __STM32F1xx_HAL_DEF 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include "stm32f1xx.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 | #define HAL_MAX_DELAY 0xFFFFFFFFU 58 | 59 | #define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != 0U) 60 | #define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) 61 | 62 | #define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ 63 | do{ \ 64 | (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ 65 | (__DMA_HANDLE__).Parent = (__HANDLE__); \ 66 | } while(0U) 67 | 68 | #define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ 69 | 70 | /** @brief Reset the Handle's State field. 71 | * @param __HANDLE__ specifies the Peripheral Handle. 72 | * @note This macro can be used for the following purpose: 73 | * - When the Handle is declared as local variable; before passing it as parameter 74 | * to HAL_PPP_Init() for the first time, it is mandatory to use this macro 75 | * to set to 0 the Handle's "State" field. 76 | * Otherwise, "State" field may have any random value and the first time the function 77 | * HAL_PPP_Init() is called, the low level hardware initialization will be missed 78 | * (i.e. HAL_PPP_MspInit() will not be executed). 79 | * - When there is a need to reconfigure the low level hardware: instead of calling 80 | * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). 81 | * In this later function, when the Handle's "State" field is set to 0, it will execute the function 82 | * HAL_PPP_MspInit() which will reconfigure the low level hardware. 83 | * @retval None 84 | */ 85 | #define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) 86 | 87 | #if (USE_RTOS == 1U) 88 | /* Reserved for future use */ 89 | #error "USE_RTOS should be 0 in the current HAL release" 90 | #else 91 | #define __HAL_LOCK(__HANDLE__) \ 92 | do{ \ 93 | if((__HANDLE__)->Lock == HAL_LOCKED) \ 94 | { \ 95 | return HAL_BUSY; \ 96 | } \ 97 | else \ 98 | { \ 99 | (__HANDLE__)->Lock = HAL_LOCKED; \ 100 | } \ 101 | }while (0U) 102 | 103 | #define __HAL_UNLOCK(__HANDLE__) \ 104 | do{ \ 105 | (__HANDLE__)->Lock = HAL_UNLOCKED; \ 106 | }while (0U) 107 | #endif /* USE_RTOS */ 108 | 109 | #if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ 110 | #ifndef __weak 111 | #define __weak __attribute__((weak)) 112 | #endif 113 | #ifndef __packed 114 | #define __packed __attribute__((packed)) 115 | #endif 116 | #elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ 117 | #ifndef __weak 118 | #define __weak __attribute__((weak)) 119 | #endif /* __weak */ 120 | #ifndef __packed 121 | #define __packed __attribute__((__packed__)) 122 | #endif /* __packed */ 123 | #endif /* __GNUC__ */ 124 | 125 | 126 | /* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ 127 | #if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ 128 | #ifndef __ALIGN_BEGIN 129 | #define __ALIGN_BEGIN 130 | #endif 131 | #ifndef __ALIGN_END 132 | #define __ALIGN_END __attribute__ ((aligned (4))) 133 | #endif 134 | #elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ 135 | #ifndef __ALIGN_END 136 | #define __ALIGN_END __attribute__ ((aligned (4))) 137 | #endif /* __ALIGN_END */ 138 | #ifndef __ALIGN_BEGIN 139 | #define __ALIGN_BEGIN 140 | #endif /* __ALIGN_BEGIN */ 141 | #else 142 | #ifndef __ALIGN_END 143 | #define __ALIGN_END 144 | #endif /* __ALIGN_END */ 145 | #ifndef __ALIGN_BEGIN 146 | #if defined (__CC_ARM) /* ARM Compiler V5*/ 147 | #define __ALIGN_BEGIN __align(4) 148 | #elif defined (__ICCARM__) /* IAR Compiler */ 149 | #define __ALIGN_BEGIN 150 | #endif /* __CC_ARM */ 151 | #endif /* __ALIGN_BEGIN */ 152 | #endif /* __GNUC__ */ 153 | 154 | 155 | /** 156 | * @brief __RAM_FUNC definition 157 | */ 158 | #if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) 159 | /* ARM Compiler V4/V5 and V6 160 | -------------------------- 161 | RAM functions are defined using the toolchain options. 162 | Functions that are executed in RAM should reside in a separate source module. 163 | Using the 'Options for File' dialog you can simply change the 'Code / Const' 164 | area of a module to a memory space in physical RAM. 165 | Available memory areas are declared in the 'Target' tab of the 'Options for Target' 166 | dialog. 167 | */ 168 | #define __RAM_FUNC 169 | 170 | #elif defined ( __ICCARM__ ) 171 | /* ICCARM Compiler 172 | --------------- 173 | RAM functions are defined using a specific toolchain keyword "__ramfunc". 174 | */ 175 | #define __RAM_FUNC __ramfunc 176 | 177 | #elif defined ( __GNUC__ ) 178 | /* GNU Compiler 179 | ------------ 180 | RAM functions are defined using a specific toolchain attribute 181 | "__attribute__((section(".RamFunc")))". 182 | */ 183 | #define __RAM_FUNC __attribute__((section(".RamFunc"))) 184 | 185 | #endif 186 | 187 | /** 188 | * @brief __NOINLINE definition 189 | */ 190 | #if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) 191 | /* ARM V4/V5 and V6 & GNU Compiler 192 | ------------------------------- 193 | */ 194 | #define __NOINLINE __attribute__ ( (noinline) ) 195 | 196 | #elif defined ( __ICCARM__ ) 197 | /* ICCARM Compiler 198 | --------------- 199 | */ 200 | #define __NOINLINE _Pragma("optimize = no_inline") 201 | 202 | #endif 203 | 204 | #ifdef __cplusplus 205 | } 206 | #endif 207 | 208 | #endif /* ___STM32F1xx_HAL_DEF */ 209 | 210 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 211 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/deprecated_definitions.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | #ifndef DEPRECATED_DEFINITIONS_H 29 | #define DEPRECATED_DEFINITIONS_H 30 | 31 | 32 | /* Each FreeRTOS port has a unique portmacro.h header file. Originally a 33 | pre-processor definition was used to ensure the pre-processor found the correct 34 | portmacro.h file for the port being used. That scheme was deprecated in favour 35 | of setting the compiler's include path such that it found the correct 36 | portmacro.h file - removing the need for the constant and allowing the 37 | portmacro.h file to be located anywhere in relation to the port being used. The 38 | definitions below remain in the code for backward compatibility only. New 39 | projects should not use them. */ 40 | 41 | #ifdef OPEN_WATCOM_INDUSTRIAL_PC_PORT 42 | #include "..\..\Source\portable\owatcom\16bitdos\pc\portmacro.h" 43 | typedef void ( __interrupt __far *pxISR )(); 44 | #endif 45 | 46 | #ifdef OPEN_WATCOM_FLASH_LITE_186_PORT 47 | #include "..\..\Source\portable\owatcom\16bitdos\flsh186\portmacro.h" 48 | typedef void ( __interrupt __far *pxISR )(); 49 | #endif 50 | 51 | #ifdef GCC_MEGA_AVR 52 | #include "../portable/GCC/ATMega323/portmacro.h" 53 | #endif 54 | 55 | #ifdef IAR_MEGA_AVR 56 | #include "../portable/IAR/ATMega323/portmacro.h" 57 | #endif 58 | 59 | #ifdef MPLAB_PIC24_PORT 60 | #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" 61 | #endif 62 | 63 | #ifdef MPLAB_DSPIC_PORT 64 | #include "../../Source/portable/MPLAB/PIC24_dsPIC/portmacro.h" 65 | #endif 66 | 67 | #ifdef MPLAB_PIC18F_PORT 68 | #include "../../Source/portable/MPLAB/PIC18F/portmacro.h" 69 | #endif 70 | 71 | #ifdef MPLAB_PIC32MX_PORT 72 | #include "../../Source/portable/MPLAB/PIC32MX/portmacro.h" 73 | #endif 74 | 75 | #ifdef _FEDPICC 76 | #include "libFreeRTOS/Include/portmacro.h" 77 | #endif 78 | 79 | #ifdef SDCC_CYGNAL 80 | #include "../../Source/portable/SDCC/Cygnal/portmacro.h" 81 | #endif 82 | 83 | #ifdef GCC_ARM7 84 | #include "../../Source/portable/GCC/ARM7_LPC2000/portmacro.h" 85 | #endif 86 | 87 | #ifdef GCC_ARM7_ECLIPSE 88 | #include "portmacro.h" 89 | #endif 90 | 91 | #ifdef ROWLEY_LPC23xx 92 | #include "../../Source/portable/GCC/ARM7_LPC23xx/portmacro.h" 93 | #endif 94 | 95 | #ifdef IAR_MSP430 96 | #include "..\..\Source\portable\IAR\MSP430\portmacro.h" 97 | #endif 98 | 99 | #ifdef GCC_MSP430 100 | #include "../../Source/portable/GCC/MSP430F449/portmacro.h" 101 | #endif 102 | 103 | #ifdef ROWLEY_MSP430 104 | #include "../../Source/portable/Rowley/MSP430F449/portmacro.h" 105 | #endif 106 | 107 | #ifdef ARM7_LPC21xx_KEIL_RVDS 108 | #include "..\..\Source\portable\RVDS\ARM7_LPC21xx\portmacro.h" 109 | #endif 110 | 111 | #ifdef SAM7_GCC 112 | #include "../../Source/portable/GCC/ARM7_AT91SAM7S/portmacro.h" 113 | #endif 114 | 115 | #ifdef SAM7_IAR 116 | #include "..\..\Source\portable\IAR\AtmelSAM7S64\portmacro.h" 117 | #endif 118 | 119 | #ifdef SAM9XE_IAR 120 | #include "..\..\Source\portable\IAR\AtmelSAM9XE\portmacro.h" 121 | #endif 122 | 123 | #ifdef LPC2000_IAR 124 | #include "..\..\Source\portable\IAR\LPC2000\portmacro.h" 125 | #endif 126 | 127 | #ifdef STR71X_IAR 128 | #include "..\..\Source\portable\IAR\STR71x\portmacro.h" 129 | #endif 130 | 131 | #ifdef STR75X_IAR 132 | #include "..\..\Source\portable\IAR\STR75x\portmacro.h" 133 | #endif 134 | 135 | #ifdef STR75X_GCC 136 | #include "..\..\Source\portable\GCC\STR75x\portmacro.h" 137 | #endif 138 | 139 | #ifdef STR91X_IAR 140 | #include "..\..\Source\portable\IAR\STR91x\portmacro.h" 141 | #endif 142 | 143 | #ifdef GCC_H8S 144 | #include "../../Source/portable/GCC/H8S2329/portmacro.h" 145 | #endif 146 | 147 | #ifdef GCC_AT91FR40008 148 | #include "../../Source/portable/GCC/ARM7_AT91FR40008/portmacro.h" 149 | #endif 150 | 151 | #ifdef RVDS_ARMCM3_LM3S102 152 | #include "../../Source/portable/RVDS/ARM_CM3/portmacro.h" 153 | #endif 154 | 155 | #ifdef GCC_ARMCM3_LM3S102 156 | #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" 157 | #endif 158 | 159 | #ifdef GCC_ARMCM3 160 | #include "../../Source/portable/GCC/ARM_CM3/portmacro.h" 161 | #endif 162 | 163 | #ifdef IAR_ARM_CM3 164 | #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" 165 | #endif 166 | 167 | #ifdef IAR_ARMCM3_LM 168 | #include "../../Source/portable/IAR/ARM_CM3/portmacro.h" 169 | #endif 170 | 171 | #ifdef HCS12_CODE_WARRIOR 172 | #include "../../Source/portable/CodeWarrior/HCS12/portmacro.h" 173 | #endif 174 | 175 | #ifdef MICROBLAZE_GCC 176 | #include "../../Source/portable/GCC/MicroBlaze/portmacro.h" 177 | #endif 178 | 179 | #ifdef TERN_EE 180 | #include "..\..\Source\portable\Paradigm\Tern_EE\small\portmacro.h" 181 | #endif 182 | 183 | #ifdef GCC_HCS12 184 | #include "../../Source/portable/GCC/HCS12/portmacro.h" 185 | #endif 186 | 187 | #ifdef GCC_MCF5235 188 | #include "../../Source/portable/GCC/MCF5235/portmacro.h" 189 | #endif 190 | 191 | #ifdef COLDFIRE_V2_GCC 192 | #include "../../../Source/portable/GCC/ColdFire_V2/portmacro.h" 193 | #endif 194 | 195 | #ifdef COLDFIRE_V2_CODEWARRIOR 196 | #include "../../Source/portable/CodeWarrior/ColdFire_V2/portmacro.h" 197 | #endif 198 | 199 | #ifdef GCC_PPC405 200 | #include "../../Source/portable/GCC/PPC405_Xilinx/portmacro.h" 201 | #endif 202 | 203 | #ifdef GCC_PPC440 204 | #include "../../Source/portable/GCC/PPC440_Xilinx/portmacro.h" 205 | #endif 206 | 207 | #ifdef _16FX_SOFTUNE 208 | #include "..\..\Source\portable\Softune\MB96340\portmacro.h" 209 | #endif 210 | 211 | #ifdef BCC_INDUSTRIAL_PC_PORT 212 | /* A short file name has to be used in place of the normal 213 | FreeRTOSConfig.h when using the Borland compiler. */ 214 | #include "frconfig.h" 215 | #include "..\portable\BCC\16BitDOS\PC\prtmacro.h" 216 | typedef void ( __interrupt __far *pxISR )(); 217 | #endif 218 | 219 | #ifdef BCC_FLASH_LITE_186_PORT 220 | /* A short file name has to be used in place of the normal 221 | FreeRTOSConfig.h when using the Borland compiler. */ 222 | #include "frconfig.h" 223 | #include "..\portable\BCC\16BitDOS\flsh186\prtmacro.h" 224 | typedef void ( __interrupt __far *pxISR )(); 225 | #endif 226 | 227 | #ifdef __GNUC__ 228 | #ifdef __AVR32_AVR32A__ 229 | #include "portmacro.h" 230 | #endif 231 | #endif 232 | 233 | #ifdef __ICCAVR32__ 234 | #ifdef __CORE__ 235 | #if __CORE__ == __AVR32A__ 236 | #include "portmacro.h" 237 | #endif 238 | #endif 239 | #endif 240 | 241 | #ifdef __91467D 242 | #include "portmacro.h" 243 | #endif 244 | 245 | #ifdef __96340 246 | #include "portmacro.h" 247 | #endif 248 | 249 | 250 | #ifdef __IAR_V850ES_Fx3__ 251 | #include "../../Source/portable/IAR/V850ES/portmacro.h" 252 | #endif 253 | 254 | #ifdef __IAR_V850ES_Jx3__ 255 | #include "../../Source/portable/IAR/V850ES/portmacro.h" 256 | #endif 257 | 258 | #ifdef __IAR_V850ES_Jx3_L__ 259 | #include "../../Source/portable/IAR/V850ES/portmacro.h" 260 | #endif 261 | 262 | #ifdef __IAR_V850ES_Jx2__ 263 | #include "../../Source/portable/IAR/V850ES/portmacro.h" 264 | #endif 265 | 266 | #ifdef __IAR_V850ES_Hx2__ 267 | #include "../../Source/portable/IAR/V850ES/portmacro.h" 268 | #endif 269 | 270 | #ifdef __IAR_78K0R_Kx3__ 271 | #include "../../Source/portable/IAR/78K0R/portmacro.h" 272 | #endif 273 | 274 | #ifdef __IAR_78K0R_Kx3L__ 275 | #include "../../Source/portable/IAR/78K0R/portmacro.h" 276 | #endif 277 | 278 | #endif /* DEPRECATED_DEFINITIONS_H */ 279 | 280 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/list.c: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | 29 | #include 30 | #include "FreeRTOS.h" 31 | #include "list.h" 32 | 33 | /*----------------------------------------------------------- 34 | * PUBLIC LIST API documented in list.h 35 | *----------------------------------------------------------*/ 36 | 37 | void vListInitialise( List_t * const pxList ) 38 | { 39 | /* The list structure contains a list item which is used to mark the 40 | end of the list. To initialise the list the list end is inserted 41 | as the only list entry. */ 42 | pxList->pxIndex = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 The mini list structure is used as the list end to save RAM. This is checked and valid. */ 43 | 44 | /* The list end value is the highest possible value in the list to 45 | ensure it remains at the end of the list. */ 46 | pxList->xListEnd.xItemValue = portMAX_DELAY; 47 | 48 | /* The list end next and previous pointers point to itself so we know 49 | when the list is empty. */ 50 | pxList->xListEnd.pxNext = ( ListItem_t * ) &( pxList->xListEnd ); /*lint !e826 !e740 The mini list structure is used as the list end to save RAM. This is checked and valid. */ 51 | pxList->xListEnd.pxPrevious = ( ListItem_t * ) &( pxList->xListEnd );/*lint !e826 !e740 The mini list structure is used as the list end to save RAM. This is checked and valid. */ 52 | 53 | pxList->uxNumberOfItems = ( UBaseType_t ) 0U; 54 | 55 | /* Write known values into the list if 56 | configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ 57 | listSET_LIST_INTEGRITY_CHECK_1_VALUE( pxList ); 58 | listSET_LIST_INTEGRITY_CHECK_2_VALUE( pxList ); 59 | } 60 | /*-----------------------------------------------------------*/ 61 | 62 | void vListInitialiseItem( ListItem_t * const pxItem ) 63 | { 64 | /* Make sure the list item is not recorded as being on a list. */ 65 | pxItem->pvContainer = NULL; 66 | 67 | /* Write known values into the list item if 68 | configUSE_LIST_DATA_INTEGRITY_CHECK_BYTES is set to 1. */ 69 | listSET_FIRST_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); 70 | listSET_SECOND_LIST_ITEM_INTEGRITY_CHECK_VALUE( pxItem ); 71 | } 72 | /*-----------------------------------------------------------*/ 73 | 74 | void vListInsertEnd( List_t * const pxList, ListItem_t * const pxNewListItem ) 75 | { 76 | ListItem_t * const pxIndex = pxList->pxIndex; 77 | 78 | /* Only effective when configASSERT() is also defined, these tests may catch 79 | the list data structures being overwritten in memory. They will not catch 80 | data errors caused by incorrect configuration or use of FreeRTOS. */ 81 | listTEST_LIST_INTEGRITY( pxList ); 82 | listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); 83 | 84 | /* Insert a new list item into pxList, but rather than sort the list, 85 | makes the new list item the last item to be removed by a call to 86 | listGET_OWNER_OF_NEXT_ENTRY(). */ 87 | pxNewListItem->pxNext = pxIndex; 88 | pxNewListItem->pxPrevious = pxIndex->pxPrevious; 89 | 90 | /* Only used during decision coverage testing. */ 91 | mtCOVERAGE_TEST_DELAY(); 92 | 93 | pxIndex->pxPrevious->pxNext = pxNewListItem; 94 | pxIndex->pxPrevious = pxNewListItem; 95 | 96 | /* Remember which list the item is in. */ 97 | pxNewListItem->pvContainer = ( void * ) pxList; 98 | 99 | ( pxList->uxNumberOfItems )++; 100 | } 101 | /*-----------------------------------------------------------*/ 102 | 103 | void vListInsert( List_t * const pxList, ListItem_t * const pxNewListItem ) 104 | { 105 | ListItem_t *pxIterator; 106 | const TickType_t xValueOfInsertion = pxNewListItem->xItemValue; 107 | 108 | /* Only effective when configASSERT() is also defined, these tests may catch 109 | the list data structures being overwritten in memory. They will not catch 110 | data errors caused by incorrect configuration or use of FreeRTOS. */ 111 | listTEST_LIST_INTEGRITY( pxList ); 112 | listTEST_LIST_ITEM_INTEGRITY( pxNewListItem ); 113 | 114 | /* Insert the new list item into the list, sorted in xItemValue order. 115 | 116 | If the list already contains a list item with the same item value then the 117 | new list item should be placed after it. This ensures that TCB's which are 118 | stored in ready lists (all of which have the same xItemValue value) get a 119 | share of the CPU. However, if the xItemValue is the same as the back marker 120 | the iteration loop below will not end. Therefore the value is checked 121 | first, and the algorithm slightly modified if necessary. */ 122 | if( xValueOfInsertion == portMAX_DELAY ) 123 | { 124 | pxIterator = pxList->xListEnd.pxPrevious; 125 | } 126 | else 127 | { 128 | /* *** NOTE *********************************************************** 129 | If you find your application is crashing here then likely causes are 130 | listed below. In addition see http://www.freertos.org/FAQHelp.html for 131 | more tips, and ensure configASSERT() is defined! 132 | http://www.freertos.org/a00110.html#configASSERT 133 | 134 | 1) Stack overflow - 135 | see http://www.freertos.org/Stacks-and-stack-overflow-checking.html 136 | 2) Incorrect interrupt priority assignment, especially on Cortex-M 137 | parts where numerically high priority values denote low actual 138 | interrupt priorities, which can seem counter intuitive. See 139 | http://www.freertos.org/RTOS-Cortex-M3-M4.html and the definition 140 | of configMAX_SYSCALL_INTERRUPT_PRIORITY on 141 | http://www.freertos.org/a00110.html 142 | 3) Calling an API function from within a critical section or when 143 | the scheduler is suspended, or calling an API function that does 144 | not end in "FromISR" from an interrupt. 145 | 4) Using a queue or semaphore before it has been initialised or 146 | before the scheduler has been started (are interrupts firing 147 | before vTaskStartScheduler() has been called?). 148 | **********************************************************************/ 149 | 150 | for( pxIterator = ( ListItem_t * ) &( pxList->xListEnd ); pxIterator->pxNext->xItemValue <= xValueOfInsertion; pxIterator = pxIterator->pxNext ) /*lint !e826 !e740 The mini list structure is used as the list end to save RAM. This is checked and valid. */ 151 | { 152 | /* There is nothing to do here, just iterating to the wanted 153 | insertion position. */ 154 | } 155 | } 156 | 157 | pxNewListItem->pxNext = pxIterator->pxNext; 158 | pxNewListItem->pxNext->pxPrevious = pxNewListItem; 159 | pxNewListItem->pxPrevious = pxIterator; 160 | pxIterator->pxNext = pxNewListItem; 161 | 162 | /* Remember which list the item is in. This allows fast removal of the 163 | item later. */ 164 | pxNewListItem->pvContainer = ( void * ) pxList; 165 | 166 | ( pxList->uxNumberOfItems )++; 167 | } 168 | /*-----------------------------------------------------------*/ 169 | 170 | UBaseType_t uxListRemove( ListItem_t * const pxItemToRemove ) 171 | { 172 | /* The list item knows which list it is in. Obtain the list from the list 173 | item. */ 174 | List_t * const pxList = ( List_t * ) pxItemToRemove->pvContainer; 175 | 176 | pxItemToRemove->pxNext->pxPrevious = pxItemToRemove->pxPrevious; 177 | pxItemToRemove->pxPrevious->pxNext = pxItemToRemove->pxNext; 178 | 179 | /* Only used during decision coverage testing. */ 180 | mtCOVERAGE_TEST_DELAY(); 181 | 182 | /* Make sure the index is left pointing to a valid item. */ 183 | if( pxList->pxIndex == pxItemToRemove ) 184 | { 185 | pxList->pxIndex = pxItemToRemove->pxPrevious; 186 | } 187 | else 188 | { 189 | mtCOVERAGE_TEST_MARKER(); 190 | } 191 | 192 | pxItemToRemove->pvContainer = NULL; 193 | ( pxList->uxNumberOfItems )--; 194 | 195 | return pxList->uxNumberOfItems; 196 | } 197 | /*-----------------------------------------------------------*/ 198 | 199 | -------------------------------------------------------------------------------- /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) 2022 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file 13 | * in the root directory of this software component. 14 | * If no LICENSE file comes with this software, it is provided AS-IS. 15 | * 16 | ****************************************************************************** 17 | */ 18 | /* USER CODE END Header */ 19 | /* Includes ------------------------------------------------------------------*/ 20 | #include "main.h" 21 | #include "cmsis_os.h" 22 | #include "adc.h" 23 | #include "can.h" 24 | #include "i2c.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 | #include 34 | #include 35 | 36 | #include "FOC.h" 37 | #include "FOC_utils.h" 38 | #include "AS5600.h" 39 | #include "current_sense.h" 40 | 41 | #include "gui.h" 42 | #include "st7735.h" 43 | 44 | #include "bsp_button.h" 45 | /* USER CODE END Includes */ 46 | 47 | /* Private typedef -----------------------------------------------------------*/ 48 | /* USER CODE BEGIN PTD */ 49 | 50 | /* USER CODE END PTD */ 51 | 52 | /* Private define ------------------------------------------------------------*/ 53 | /* USER CODE BEGIN PD */ 54 | /* USER CODE END PD */ 55 | 56 | /* Private macro -------------------------------------------------------------*/ 57 | /* USER CODE BEGIN PM */ 58 | 59 | /* USER CODE END PM */ 60 | 61 | /* Private variables ---------------------------------------------------------*/ 62 | 63 | /* USER CODE BEGIN PV */ 64 | 65 | /* USER CODE END PV */ 66 | 67 | /* Private function prototypes -----------------------------------------------*/ 68 | void SystemClock_Config(void); 69 | void MX_FREERTOS_Init(void); 70 | /* USER CODE BEGIN PFP */ 71 | 72 | /* USER CODE END PFP */ 73 | 74 | /* Private user code ---------------------------------------------------------*/ 75 | /* USER CODE BEGIN 0 */ 76 | 77 | /* USER CODE END 0 */ 78 | 79 | /** 80 | * @brief The application entry point. 81 | * @retval int 82 | */ 83 | int main(void) 84 | { 85 | /* USER CODE BEGIN 1 */ 86 | 87 | /* USER CODE END 1 */ 88 | 89 | /* MCU Configuration--------------------------------------------------------*/ 90 | 91 | /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ 92 | HAL_Init(); 93 | 94 | /* USER CODE BEGIN Init */ 95 | 96 | /* USER CODE END Init */ 97 | 98 | /* Configure the system clock */ 99 | SystemClock_Config(); 100 | 101 | /* USER CODE BEGIN SysInit */ 102 | 103 | /* USER CODE END SysInit */ 104 | 105 | /* Initialize all configured peripherals */ 106 | MX_GPIO_Init(); 107 | MX_ADC1_Init(); 108 | MX_CAN_Init(); 109 | MX_I2C1_Init(); 110 | MX_SPI1_Init(); 111 | MX_TIM1_Init(); 112 | MX_USART1_UART_Init(); 113 | /* USER CODE BEGIN 2 */ 114 | ST7735_Init(); 115 | 116 | gui_draw_init("FOC init", 1); 117 | FOC_init(); 118 | 119 | gui_draw_init("CS init", 0); 120 | cs_init(); 121 | 122 | gui_draw_init("Calibrating", 0); 123 | FOC_electrical_angle_calibration(); 124 | /* USER CODE END 2 */ 125 | 126 | /* Call init function for freertos objects (in freertos.c) */ 127 | MX_FREERTOS_Init(); 128 | 129 | /* Start scheduler */ 130 | osKernelStart(); 131 | 132 | /* We should never get here as control is now taken by the scheduler */ 133 | /* Infinite loop */ 134 | /* USER CODE BEGIN WHILE */ 135 | while (1) { 136 | 137 | 138 | 139 | // char display_string[40]; 140 | // char display_number[20]; 141 | 142 | 143 | // 144 | // strcpy(display_string, "ElectricalAngle:"); 145 | // itoa((int) (angle * _RADIAN_TO_DEGREE), display_number, 10); 146 | // strcat(display_string, display_number); 147 | // ST7735_WriteString(0, 36, display_string, Font_7x10, ST7735_RED, ST7735_WHITE); 148 | // 149 | // strcpy(display_string, "MechanicalAngle:"); 150 | // itoa(mechanical_angle, display_number, 10); 151 | // strcat(display_string, display_number); 152 | // ST7735_WriteString(0, 46, display_string, Font_7x10, ST7735_RED, ST7735_WHITE); 153 | // 154 | // itoa((int16_t)cs_value[0] - 2030, display_string,10); 155 | // ST7735_WriteString(0, 56, display_string, Font_7x10, ST7735_RED, ST7735_WHITE); 156 | // 157 | // itoa((int16_t)cs_value[1] - 2030, display_string,10); 158 | // ST7735_WriteString(0, 66, display_string, Font_7x10, ST7735_RED, ST7735_WHITE); 159 | // 160 | // itoa((int16_t)cs_value[2] - 2030, display_string,10); 161 | // ST7735_WriteString(0, 76, display_string, Font_7x10, ST7735_RED, ST7735_WHITE); 162 | // HAL_Delay(1); 163 | 164 | 165 | /* USER CODE END WHILE */ 166 | 167 | /* USER CODE BEGIN 3 */ 168 | } 169 | /* USER CODE END 3 */ 170 | } 171 | 172 | /** 173 | * @brief System Clock Configuration 174 | * @retval None 175 | */ 176 | void SystemClock_Config(void) 177 | { 178 | RCC_OscInitTypeDef RCC_OscInitStruct = {0}; 179 | RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; 180 | RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; 181 | 182 | /** Initializes the RCC Oscillators according to the specified parameters 183 | * in the RCC_OscInitTypeDef structure. 184 | */ 185 | RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE; 186 | RCC_OscInitStruct.HSEState = RCC_HSE_ON; 187 | RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1; 188 | RCC_OscInitStruct.HSIState = RCC_HSI_ON; 189 | RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; 190 | RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE; 191 | RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9; 192 | if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) 193 | { 194 | Error_Handler(); 195 | } 196 | 197 | /** Initializes the CPU, AHB and APB buses clocks 198 | */ 199 | RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK 200 | |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; 201 | RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; 202 | RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; 203 | RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; 204 | RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; 205 | 206 | if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) 207 | { 208 | Error_Handler(); 209 | } 210 | PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_ADC; 211 | PeriphClkInit.AdcClockSelection = RCC_ADCPCLK2_DIV6; 212 | if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) 213 | { 214 | Error_Handler(); 215 | } 216 | } 217 | 218 | /* USER CODE BEGIN 4 */ 219 | 220 | /* USER CODE END 4 */ 221 | 222 | /** 223 | * @brief Period elapsed callback in non blocking mode 224 | * @note This function is called when TIM4 interrupt took place, inside 225 | * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment 226 | * a global variable "uwTick" used as application time base. 227 | * @param htim : TIM handle 228 | * @retval None 229 | */ 230 | void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) 231 | { 232 | /* USER CODE BEGIN Callback 0 */ 233 | 234 | /* USER CODE END Callback 0 */ 235 | if (htim->Instance == TIM4) { 236 | HAL_IncTick(); 237 | } 238 | /* USER CODE BEGIN Callback 1 */ 239 | // if (htim->Instance == TIM1) { 240 | // if(__HAL_TIM_IS_TIM_COUNTING_DOWN(htim)) { 241 | // cs_get_value(); 242 | // } 243 | // } 244 | /* USER CODE END Callback 1 */ 245 | } 246 | 247 | /** 248 | * @brief This function is executed in case of error occurrence. 249 | * @retval None 250 | */ 251 | void Error_Handler(void) 252 | { 253 | /* USER CODE BEGIN Error_Handler_Debug */ 254 | /* User can add his own implementation to report the HAL error return state */ 255 | __disable_irq(); 256 | while (1) { 257 | } 258 | /* USER CODE END Error_Handler_Debug */ 259 | } 260 | 261 | #ifdef USE_FULL_ASSERT 262 | /** 263 | * @brief Reports the name of the source file and the source line number 264 | * where the assert_param error has occurred. 265 | * @param file: pointer to the source file name 266 | * @param line: assert_param error line source number 267 | * @retval None 268 | */ 269 | void assert_failed(uint8_t *file, uint32_t line) 270 | { 271 | /* USER CODE BEGIN 6 */ 272 | /* User can add his own implementation to report the file name and line number, 273 | ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ 274 | /* USER CODE END 6 */ 275 | } 276 | #endif /* USE_FULL_ASSERT */ 277 | -------------------------------------------------------------------------------- /FOC/FOC.c: -------------------------------------------------------------------------------- 1 | /** 2 | * @file FOC.c 3 | * @author Aiano_czm 4 | */ 5 | 6 | #include 7 | #include 8 | #include "FOC.h" 9 | #include "FOC_conf.h" 10 | #include "FOC_utils.h" 11 | #include "FOC_PID.h" 12 | #include "FOC_LPF.h" 13 | #include "hardware_api.h" 14 | #include "AS5600.h" 15 | #include "current_sense.h" 16 | #include "usart.h" 17 | 18 | 19 | float zero_mechanical_angle = 0.36; 20 | float zero_electrical_angle = 0.891460538; 21 | 22 | float last_mechanical_angle = 0; 23 | uint32_t pre_tick; 24 | 25 | 26 | void FOC_init() { 27 | AS5600_init(); 28 | _init3PWM(); 29 | pid_set_parameters(); 30 | FOC_lpf_set_parameters(); 31 | pre_tick = HAL_GetTick(); 32 | } 33 | 34 | void FOC_electrical_angle_calibration() { 35 | // FOC calibration 36 | FOC_SVPWM(0, 8, 0); 37 | HAL_Delay(400); 38 | zero_electrical_angle = FOC_electrical_angle(); 39 | HAL_Delay(100); 40 | FOC_SVPWM(0, 0, 0); 41 | } 42 | 43 | void FOC_SVPWM(float Uq, float Ud, float angle) { 44 | 45 | int sector; 46 | 47 | // Nice video explaining the SpaceVectorModulation (FOC_SVPWM) algorithm 48 | // https://www.youtube.com/watch?v=QMSWUMEAejg 49 | 50 | // the algorithm goes 51 | // 1) Ualpha, Ubeta 52 | // 2) Uout = sqrt(Ualpha^2 + Ubeta^2) 53 | // 3) angle_el = atan2(Ubeta, Ualpha) 54 | // 55 | // equivalent to 2) because the magnitude does not change is: 56 | // Uout = sqrt(Ud^2 + Uq^2) 57 | // equivalent to 3) is 58 | // angle_el = angle_el + atan2(Uq,Ud) 59 | 60 | float Uout = _sqrt(Ud * Ud + Uq * Uq) / VOLTAGE_LIMIT; // Actually, Uout is a ratio 61 | angle = _normalizeAngle(angle + atan2(Uq, Ud)); 62 | 63 | // find the sector we are in currently 64 | sector = floor(angle / _PI_3) + 1; 65 | // calculate the duty cycles 66 | float T1 = _SQRT3 * _sin(sector * _PI_3 - angle) * Uout; 67 | float T2 = _SQRT3 * _sin(angle - (sector - 1.0f) * _PI_3) * Uout; 68 | // two versions possible 69 | // float T0 = 0; // pulled to 0 - better for low power supply voltage 70 | float T0 = 1 - T1 - T2; // modulation_centered around driver->voltage_limit/2 71 | 72 | 73 | // calculate the duty cycles(times) 74 | float Ta, Tb, Tc; 75 | switch (sector) { 76 | case 1: 77 | Ta = T1 + T2 + T0 / 2; 78 | Tb = T2 + T0 / 2; 79 | Tc = T0 / 2; 80 | break; 81 | case 2: 82 | Ta = T1 + T0 / 2; 83 | Tb = T1 + T2 + T0 / 2; 84 | Tc = T0 / 2; 85 | break; 86 | case 3: 87 | Ta = T0 / 2; 88 | Tb = T1 + T2 + T0 / 2; 89 | Tc = T2 + T0 / 2; 90 | break; 91 | case 4: 92 | Ta = T0 / 2; 93 | Tb = T1 + T0 / 2; 94 | Tc = T1 + T2 + T0 / 2; 95 | break; 96 | case 5: 97 | Ta = T2 + T0 / 2; 98 | Tb = T0 / 2; 99 | Tc = T1 + T2 + T0 / 2; 100 | break; 101 | case 6: 102 | Ta = T1 + T2 + T0 / 2; 103 | Tb = T0 / 2; 104 | Tc = T1 + T0 / 2; 105 | break; 106 | default: 107 | // possible error state 108 | Ta = 0; 109 | Tb = 0; 110 | Tc = 0; 111 | } 112 | 113 | // Ta, Tb, Tc range [0,1] 114 | 115 | _writeDutyCycle3PWM(Ta, Tb, Tc); 116 | } 117 | 118 | void FOC_Clarke_Park(float Ia, float Ib, float Ic, float angle, float *Id, float *Iq) { 119 | // Clarke transform 120 | float mid = (1.f / 3) * (Ia + Ib + Ic); 121 | float a = Ia - mid; 122 | float b = Ib - mid; 123 | float i_alpha = a; 124 | float i_beta = _1_SQRT3 * a + _2_SQRT3 * b; 125 | 126 | // Park transform 127 | float ct = _cos(angle); 128 | float st = _sin(angle); 129 | *Id = i_alpha * ct + i_beta * st; 130 | *Iq = i_beta * ct - i_alpha * st; 131 | 132 | return; 133 | } 134 | 135 | float FOC_get_mechanical_angle() { 136 | return AS5600_ReadSensorRawData() / SENSOR_VALUE_RANGE * _2PI; 137 | } 138 | 139 | float FOC_electrical_angle() { 140 | 141 | return _normalizeAngle(SENSOR_DIRECTION * POLE_PAIR * FOC_get_mechanical_angle() - zero_electrical_angle); 142 | } 143 | 144 | // rad/s 145 | float FOC_get_velocity() { 146 | float ts = (float) (HAL_GetTick() - pre_tick) * 1e-3; 147 | if (ts < 1e-3) ts = 1e-3; 148 | pre_tick = HAL_GetTick(); 149 | 150 | float now_mechanical_angle = FOC_get_mechanical_angle(); 151 | float delta_angle = now_mechanical_angle - last_mechanical_angle; 152 | last_mechanical_angle = now_mechanical_angle; 153 | if (fabs(delta_angle) > _PI) { 154 | if (delta_angle > 0) { 155 | delta_angle -= _2PI; 156 | } else { 157 | delta_angle += _2PI; 158 | } 159 | } 160 | 161 | 162 | // return delta_angle; 163 | return delta_angle / ts; 164 | } 165 | 166 | void FOC_open_loop_voltage_control_loop(float Uq) { 167 | float electrical_angle = FOC_electrical_angle(); 168 | 169 | // Current sense 170 | float Id, Iq; 171 | cs_get_value(); 172 | FOC_Clarke_Park(cs_value[0], cs_value[1], cs_value[2], electrical_angle, &Id, &Iq); 173 | Id = FOC_low_pass_filter(&lpf_current_d, Id); 174 | Iq = FOC_low_pass_filter(&lpf_current_q, Iq); 175 | 176 | FOC_SVPWM(Uq, 0, electrical_angle); 177 | 178 | // debug 179 | printf("%.1f,%.1f,%.1f,%.1f,%.1f\n", cs_value[0], cs_value[1], cs_value[2], Id, Iq); 180 | } 181 | 182 | void FOC_current_control_loop(float target_Iq){ 183 | static float electrical_angle; 184 | electrical_angle = FOC_electrical_angle(); 185 | 186 | // Current sense 187 | static float Id, Iq; 188 | cs_get_value(); 189 | FOC_Clarke_Park(cs_value[0], cs_value[1], cs_value[2], electrical_angle, &Id, &Iq); 190 | Id = FOC_low_pass_filter(&lpf_current_d, Id); 191 | Iq = FOC_low_pass_filter(&lpf_current_q, Iq); 192 | 193 | // back feed 194 | static float Uq, Ud; 195 | Uq = pid_get_u(&pid_current_q, target_Iq, Iq); 196 | Ud = pid_get_u(&pid_current_d, 0, Id); 197 | 198 | // front feed 199 | Uq += 0.008 * Iq; 200 | 201 | FOC_SVPWM(Uq, Ud, electrical_angle); 202 | 203 | // debug 204 | // printf("%.1f,%.1f,%.1f,%.1f,%.1f\n", cs_value[0], cs_value[1], cs_value[2], Id, Iq); 205 | } 206 | 207 | /** 208 | * 209 | * @param target_velocity unit: rad/s 210 | */ 211 | void FOC_velocity_control_loop(float target_velocity) { 212 | static float now_velocity; 213 | now_velocity = FOC_low_pass_filter(&lpf_velocity, FOC_get_velocity()); 214 | float Uq = pid_get_u(&pid_velocity, target_velocity, now_velocity); 215 | float electrical_angle = FOC_electrical_angle(); 216 | FOC_SVPWM(Uq, 0, electrical_angle); 217 | 218 | // cs_get_value(); 219 | // printf("%d,%d,%d\n", cs_value[0], cs_value[1], cs_value[2]); 220 | } 221 | 222 | void FOC_position_control_loop(float target_angle) { 223 | target_angle = _normalizeAngle(target_angle); 224 | float now_angle = _normalizeAngle(FOC_get_mechanical_angle() - zero_mechanical_angle); 225 | // float now_angle = FOC_get_mechanical_angle(); 226 | 227 | float angle_error = target_angle - now_angle; 228 | if (angle_error < -_PI) target_angle += _2PI; 229 | else if (angle_error > _PI) target_angle -= _2PI; 230 | 231 | float target_velocity = pid_get_u(&pid_position, target_angle, now_angle); 232 | float now_velocity = FOC_low_pass_filter(&lpf_velocity, FOC_get_velocity()); 233 | float Uq = pid_get_u(&pid_velocity, target_velocity, now_velocity); 234 | float electrical_angle = FOC_electrical_angle(); 235 | FOC_SVPWM(Uq, 0, electrical_angle); 236 | 237 | //printf("%.2f,%.2f,%.2f,%.2f\n", target_angle, now_angle, target_velocity, now_velocity); 238 | } 239 | 240 | void FOC_spring_loop(float target_angle, PID_Datatype *pid) { 241 | target_angle = _normalizeAngle(target_angle); 242 | float now_angle = _normalizeAngle(FOC_get_mechanical_angle() - zero_mechanical_angle); 243 | 244 | float angle_error = target_angle - now_angle; 245 | if (angle_error < -_PI) target_angle += _2PI; 246 | else if (angle_error > _PI) target_angle -= _2PI; 247 | 248 | float Uq = FOC_low_pass_filter(&lpf_spring, pid_get_u(pid, target_angle, now_angle)); 249 | float electrical_angle = FOC_electrical_angle(); 250 | FOC_SVPWM(Uq, 0, electrical_angle); 251 | } 252 | 253 | void FOC_knob_loop(uint8_t sector_num) { 254 | float now_angle = _normalizeAngle(FOC_get_mechanical_angle() - zero_mechanical_angle); 255 | uint8_t now_sector = (uint8_t) floor(now_angle * sector_num / _2PI); 256 | float target_angle = now_sector * _2PI / sector_num + _PI / sector_num; 257 | 258 | float angle_error = target_angle - now_angle; 259 | if (angle_error < -_PI) target_angle += _2PI; 260 | else if (angle_error > _PI) target_angle -= _2PI; 261 | 262 | float Uq = pid_get_u(&pid_knob, target_angle, now_angle); 263 | 264 | float electrical_angle = FOC_electrical_angle(); 265 | FOC_SVPWM(Uq, 0, electrical_angle); 266 | 267 | char data = now_sector + '0'; 268 | 269 | HAL_UART_Transmit(&huart1, &data, 1, 0xff); 270 | } 271 | 272 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM3/portmacro.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.0.1 3 | * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved. 4 | * 5 | * Permission is hereby granted, free of charge, to any person obtaining a copy of 6 | * this software and associated documentation files (the "Software"), to deal in 7 | * the Software without restriction, including without limitation the rights to 8 | * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 9 | * the Software, and to permit persons to whom the Software is furnished to do so, 10 | * 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, FITNESS 17 | * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 18 | * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 19 | * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 20 | * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 21 | * 22 | * http://www.FreeRTOS.org 23 | * http://aws.amazon.com/freertos 24 | * 25 | * 1 tab == 4 spaces! 26 | */ 27 | 28 | 29 | #ifndef PORTMACRO_H 30 | #define PORTMACRO_H 31 | 32 | #ifdef __cplusplus 33 | extern "C" { 34 | #endif 35 | 36 | /*----------------------------------------------------------- 37 | * Port specific definitions. 38 | * 39 | * The settings in this file configure FreeRTOS correctly for the 40 | * given hardware and compiler. 41 | * 42 | * These settings should not be altered. 43 | *----------------------------------------------------------- 44 | */ 45 | 46 | /* Type definitions. */ 47 | #define portCHAR char 48 | #define portFLOAT float 49 | #define portDOUBLE double 50 | #define portLONG long 51 | #define portSHORT short 52 | #define portSTACK_TYPE uint32_t 53 | #define portBASE_TYPE long 54 | 55 | typedef portSTACK_TYPE StackType_t; 56 | typedef long BaseType_t; 57 | typedef unsigned long UBaseType_t; 58 | 59 | #if( configUSE_16_BIT_TICKS == 1 ) 60 | typedef uint16_t TickType_t; 61 | #define portMAX_DELAY ( TickType_t ) 0xffff 62 | #else 63 | typedef uint32_t TickType_t; 64 | #define portMAX_DELAY ( TickType_t ) 0xffffffffUL 65 | 66 | /* 32-bit tick type on a 32-bit architecture, so reads of the tick count do 67 | not need to be guarded with a critical section. */ 68 | #define portTICK_TYPE_IS_ATOMIC 1 69 | #endif 70 | /*-----------------------------------------------------------*/ 71 | 72 | /* Architecture specifics. */ 73 | #define portSTACK_GROWTH ( -1 ) 74 | #define portTICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ ) 75 | #define portBYTE_ALIGNMENT 8 76 | /*-----------------------------------------------------------*/ 77 | 78 | /* Scheduler utilities. */ 79 | #define portYIELD() \ 80 | { \ 81 | /* Set a PendSV to request a context switch. */ \ 82 | portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT; \ 83 | \ 84 | /* Barriers are normally not required but do ensure the code is completely \ 85 | within the specified behaviour for the architecture. */ \ 86 | __asm volatile( "dsb" ::: "memory" ); \ 87 | __asm volatile( "isb" ); \ 88 | } 89 | 90 | #define portNVIC_INT_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000ed04 ) ) 91 | #define portNVIC_PENDSVSET_BIT ( 1UL << 28UL ) 92 | #define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired != pdFALSE ) portYIELD() 93 | #define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x ) 94 | /*-----------------------------------------------------------*/ 95 | 96 | /* Critical section management. */ 97 | extern void vPortEnterCritical( void ); 98 | extern void vPortExitCritical( void ); 99 | #define portSET_INTERRUPT_MASK_FROM_ISR() ulPortRaiseBASEPRI() 100 | #define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortSetBASEPRI(x) 101 | #define portDISABLE_INTERRUPTS() vPortRaiseBASEPRI() 102 | #define portENABLE_INTERRUPTS() vPortSetBASEPRI(0) 103 | #define portENTER_CRITICAL() vPortEnterCritical() 104 | #define portEXIT_CRITICAL() vPortExitCritical() 105 | 106 | /*-----------------------------------------------------------*/ 107 | 108 | /* Task function macros as described on the FreeRTOS.org WEB site. These are 109 | not necessary for to use this port. They are defined so the common demo files 110 | (which build with all the ports) will build. */ 111 | #define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters ) 112 | #define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters ) 113 | /*-----------------------------------------------------------*/ 114 | 115 | /* Tickless idle/low power functionality. */ 116 | #ifndef portSUPPRESS_TICKS_AND_SLEEP 117 | extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime ); 118 | #define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime ) 119 | #endif 120 | /*-----------------------------------------------------------*/ 121 | 122 | /* Architecture specific optimisations. */ 123 | #ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION 124 | #define configUSE_PORT_OPTIMISED_TASK_SELECTION 1 125 | #endif 126 | 127 | #if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1 128 | 129 | /* Generic helper function. */ 130 | __attribute__( ( always_inline ) ) static inline uint8_t ucPortCountLeadingZeros( uint32_t ulBitmap ) 131 | { 132 | uint8_t ucReturn; 133 | 134 | __asm volatile ( "clz %0, %1" : "=r" ( ucReturn ) : "r" ( ulBitmap ) : "memory" ); 135 | return ucReturn; 136 | } 137 | 138 | /* Check the configuration. */ 139 | #if( configMAX_PRIORITIES > 32 ) 140 | #error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice. 141 | #endif 142 | 143 | /* Store/clear the ready priorities in a bit map. */ 144 | #define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) ) 145 | #define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) ) 146 | 147 | /*-----------------------------------------------------------*/ 148 | 149 | #define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31UL - ( uint32_t ) ucPortCountLeadingZeros( ( uxReadyPriorities ) ) ) 150 | 151 | #endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */ 152 | 153 | /*-----------------------------------------------------------*/ 154 | 155 | #ifdef configASSERT 156 | void vPortValidateInterruptPriority( void ); 157 | #define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority() 158 | #endif 159 | 160 | /* portNOP() is not required by this port. */ 161 | #define portNOP() 162 | 163 | #define portINLINE __inline 164 | 165 | #ifndef portFORCE_INLINE 166 | #define portFORCE_INLINE inline __attribute__(( always_inline)) 167 | #endif 168 | 169 | portFORCE_INLINE static BaseType_t xPortIsInsideInterrupt( void ) 170 | { 171 | uint32_t ulCurrentInterrupt; 172 | BaseType_t xReturn; 173 | 174 | /* Obtain the number of the currently executing interrupt. */ 175 | __asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" ); 176 | 177 | if( ulCurrentInterrupt == 0 ) 178 | { 179 | xReturn = pdFALSE; 180 | } 181 | else 182 | { 183 | xReturn = pdTRUE; 184 | } 185 | 186 | return xReturn; 187 | } 188 | 189 | /*-----------------------------------------------------------*/ 190 | 191 | portFORCE_INLINE static void vPortRaiseBASEPRI( void ) 192 | { 193 | uint32_t ulNewBASEPRI; 194 | 195 | __asm volatile 196 | ( 197 | " mov %0, %1 \n" \ 198 | " msr basepri, %0 \n" \ 199 | " isb \n" \ 200 | " dsb \n" \ 201 | :"=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory" 202 | ); 203 | } 204 | 205 | /*-----------------------------------------------------------*/ 206 | 207 | portFORCE_INLINE static uint32_t ulPortRaiseBASEPRI( void ) 208 | { 209 | uint32_t ulOriginalBASEPRI, ulNewBASEPRI; 210 | 211 | __asm volatile 212 | ( 213 | " mrs %0, basepri \n" \ 214 | " mov %1, %2 \n" \ 215 | " msr basepri, %1 \n" \ 216 | " isb \n" \ 217 | " dsb \n" \ 218 | :"=r" (ulOriginalBASEPRI), "=r" (ulNewBASEPRI) : "i" ( configMAX_SYSCALL_INTERRUPT_PRIORITY ) : "memory" 219 | ); 220 | 221 | /* This return will not be reached but is necessary to prevent compiler 222 | warnings. */ 223 | return ulOriginalBASEPRI; 224 | } 225 | /*-----------------------------------------------------------*/ 226 | 227 | portFORCE_INLINE static void vPortSetBASEPRI( uint32_t ulNewMaskValue ) 228 | { 229 | __asm volatile 230 | ( 231 | " msr basepri, %0 " :: "r" ( ulNewMaskValue ) : "memory" 232 | ); 233 | } 234 | /*-----------------------------------------------------------*/ 235 | 236 | 237 | #ifdef __cplusplus 238 | } 239 | #endif 240 | 241 | #endif /* PORTMACRO_H */ 242 | 243 | --------------------------------------------------------------------------------