├── Doc ├── for_developer.md ├── Images │ ├── PCB.jpg │ ├── SWD接口.png │ └── 电机渲染图.png └── for_user.md ├── .gitignore ├── UserLib ├── LetterShell │ ├── Inc │ │ ├── shell_cfg_user.h │ │ ├── shell_ext.h │ │ ├── shell_cfg.h │ │ └── shell_cpp.h │ ├── readme.md │ ├── CMakeLists.txt │ └── Src │ │ ├── shell_companion.c │ │ └── shell_cmd_list.c ├── PID │ ├── CMakeLists.txt │ └── PID.h └── FOC │ ├── CMakeLists.txt │ ├── base_classes │ ├── CurrentSensor.h │ ├── Encoder.h │ ├── Storage.h │ ├── BLDC_Driver.h │ └── Filter.h │ └── readme.md ├── Drivers ├── CMSIS │ ├── Device │ │ └── ST │ │ │ └── STM32G4xx │ │ │ ├── Include │ │ │ ├── stm32g4xx.h │ │ │ └── system_stm32g4xx.h │ │ │ └── LICENSE.txt │ └── Include │ │ ├── cmsis_version.h │ │ └── tz_context.h └── STM32G4xx_HAL_Driver │ ├── LICENSE.txt │ ├── Inc │ ├── stm32g4xx_hal_spi_ex.h │ ├── stm32g4xx_hal_flash_ramfunc.h │ ├── stm32g4xx_hal_pcd_ex.h │ └── stm32g4xx_hal_flash_ex.h │ └── Src │ └── stm32g4xx_hal_spi_ex.c ├── Applications ├── Src │ ├── DebugTask.cpp │ ├── CommunicationProtocol.md │ ├── FOCTask.cpp │ └── CommunicateTask.cpp ├── Inc │ ├── task_public.h │ └── FOC_config.h └── Shell │ └── StartShell.cpp ├── readme.md ├── BSP ├── retarget │ ├── retarget.h │ ├── CharCircularQueue.h │ ├── CDC_Tx_DualBuffer.h │ ├── retarget.cpp │ └── printf.h ├── Storage_EmbeddedFlash.h ├── CurrentSensor_Embed.h ├── Encoder_MT6825.h ├── BLDC_Driver_FD6288.h ├── sys_public.h └── Storage_EmbeddedFlash.cpp ├── Middlewares ├── Third_Party │ └── FreeRTOS │ │ └── Source │ │ ├── LICENSE │ │ ├── CMSIS_RTOS_V2 │ │ └── freertos_mpool.h │ │ └── include │ │ ├── projdefs.h │ │ ├── stack_macros.h │ │ └── StackMacros.h └── ST │ └── STM32_USB_Device_Library │ ├── Core │ ├── Inc │ │ ├── usbd_ctlreq.h │ │ ├── usbd_ioreq.h │ │ └── usbd_core.h │ └── Src │ │ └── usbd_ioreq.c │ └── Class │ └── CDC │ └── Inc │ └── usbd_cdc.h ├── Core ├── Inc │ ├── gpio.h │ ├── spi.h │ ├── fdcan.h │ ├── adc.h │ ├── tim.h │ ├── stm32g4xx_it.h │ └── main.h └── Src │ ├── gpio.c │ ├── stm32g4xx_hal_msp.c │ ├── sysmem.c │ ├── spi.c │ ├── syscalls.c │ ├── fdcan.c │ ├── app_freertos.c │ └── main.c ├── CMakePresets.json ├── cmake ├── gcc-arm-none-eabi.cmake └── stm32cubemx │ └── CMakeLists.txt ├── USB_Device ├── App │ ├── usb_device.h │ ├── usb_device.c │ ├── usbd_cdc_if.h │ └── usbd_desc.h └── Target │ └── usbd_conf.h └── CMakeLists.txt /Doc/for_developer.md: -------------------------------------------------------------------------------- 1 | # 自己看代码 -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | .idea 2 | build 3 | cmake-build-debug 4 | *.jdebug 5 | *.jdebug.user -------------------------------------------------------------------------------- /Doc/Images/PCB.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Liu-Curiousity/QDrive-Software/HEAD/Doc/Images/PCB.jpg -------------------------------------------------------------------------------- /Doc/Images/SWD接口.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Liu-Curiousity/QDrive-Software/HEAD/Doc/Images/SWD接口.png -------------------------------------------------------------------------------- /Doc/Images/电机渲染图.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Liu-Curiousity/QDrive-Software/HEAD/Doc/Images/电机渲染图.png -------------------------------------------------------------------------------- /UserLib/LetterShell/Inc/shell_cfg_user.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #define SHELL_GET_TICK() HAL_GetTick() 4 | #define SHELL_DEFAULT_USER "QDrive" -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g4xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Liu-Curiousity/QDrive-Software/HEAD/Drivers/CMSIS/Device/ST/STM32G4xx/Include/stm32g4xx.h -------------------------------------------------------------------------------- /UserLib/LetterShell/readme.md: -------------------------------------------------------------------------------- 1 | ## Acknowledgements 2 | 3 | 本项目LetterShell部分代码参考并改自以下开源项目: 4 | 5 | - [letter_shell](https://github.com/NevermindZZT/letter-shell) - 协议: MIT 6 | 7 | 感谢以上项目的作者们的贡献 🙏 -------------------------------------------------------------------------------- /Applications/Src/DebugTask.cpp: -------------------------------------------------------------------------------- 1 | #include "task_public.h" 2 | #include "task.h" 3 | 4 | void StartDebugTask(void *argument) { 5 | vTaskDelete(nullptr); 6 | for (;;) { 7 | delay(1000); 8 | } 9 | } 10 | -------------------------------------------------------------------------------- /UserLib/PID/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.30) 2 | 3 | project(pid) 4 | 5 | add_library(pid INTERFACE) 6 | 7 | target_sources(pid INTERFACE) 8 | 9 | target_include_directories(pid INTERFACE 10 | ./ 11 | ) -------------------------------------------------------------------------------- /UserLib/FOC/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.30) 2 | 3 | project(foc) 4 | 5 | add_library(foc INTERFACE) 6 | 7 | target_sources(foc INTERFACE FOC.cpp) 8 | 9 | target_include_directories(foc INTERFACE 10 | ./ 11 | ./base_classes 12 | ) -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32G4xx/LICENSE.txt: -------------------------------------------------------------------------------- 1 | This software component is provided to you as part of a software package and 2 | applicable license terms are in the Package_license file. If you received this 3 | software component outside of a package or without applicable license terms, 4 | the terms of the Apache-2.0 license shall apply. 5 | You may obtain a copy of the Apache-2.0 at: 6 | https://opensource.org/licenses/Apache-2.0 7 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/LICENSE.txt: -------------------------------------------------------------------------------- 1 | This software component is provided to you as part of a software package and 2 | applicable license terms are in the Package_license file. If you received this 3 | software component outside of a package or without applicable license terms, 4 | the terms of the BSD-3-Clause license shall apply. 5 | You may obtain a copy of the BSD-3-Clause at: 6 | https://opensource.org/licenses/BSD-3-Clause 7 | -------------------------------------------------------------------------------- /UserLib/LetterShell/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.30) 2 | 3 | project(letter_shell) 4 | 5 | add_library(letter_shell INTERFACE) 6 | 7 | target_compile_definitions(letter_shell INTERFACE SHELL_CFG_USER="shell_cfg_user.h") 8 | 9 | target_sources(letter_shell INTERFACE 10 | ./Src/shell.c 11 | ./Src/shell_cmd_list.c 12 | ./Src/shell_companion.c 13 | ./Src/shell_ext.c 14 | ) 15 | 16 | target_include_directories(letter_shell INTERFACE 17 | ./Inc 18 | ) -------------------------------------------------------------------------------- /readme.md: -------------------------------------------------------------------------------- 1 | # QDrive - 高性能轻量化FOC实例 2 | 3 | 此为软件部分,硬件部分参见:[QDrive-硬件部分](https://github.com/Liu-Curiousity/QDrive-Hardware) 4 | 5 | 您可以复刻此项目的硬件部分,或购买QDrive成品驱动板:[QDrive成品驱动板](https://e.tb.cn/h.hvxbdqyMjSPHMGw?tk=HijG4lsnjo0)。 6 | 7 | ![ "PCB"](./Doc/Images/PCB.jpg) 8 | 9 | [//]: # (![](./Doc/Images/PCB渲染图.png "PCB渲染图")) 10 | 11 | [//]: # () 12 | 13 | [//]: # (![](./Doc/Images/电机渲染图.png "电机渲染图")) 14 | 15 | ## 简介 16 | 17 | QDrive是一个基于STM32G431系列MCU的高性能FOC控制器,旨在提供一个轻量级、易于使用的FOC解决方案。支持多种电机类型,并且具有高效的电流控制和速度控制功能。 18 | 19 | 此工程仅适用于4310电机QDrive驱动板,如需使用其他电机,可以自行移植。 20 | 21 | ## 特性 22 | 23 | - **高性能**:基于STM32G431系列MCU,提供强大的处理能力。 24 | - **高精度**:采用18位编码器,可以实现0.005°的精细角度控制。 25 | - **ms级响应**:经测试,可在40ms内使电机转动半圈。 26 | - **丰富接口**:支持CAN总线通信、USB串口通信、支持shell交互。 27 | 28 | ## 使用方法 29 | 30 | - [**对于开发者**](./Doc/for_developer.md) 31 | - [**对于使用者**](./Doc/for_user.md) 32 | -------------------------------------------------------------------------------- /Applications/Inc/task_public.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief FreeRTOS任务公共头文件 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 24-11-24 6 | * @version V1.0.0 7 | * @note 任务函数必须在此文件定义,否则在app_freertos.c中找不到该函数符号 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于24-11-24 11 | * */ 12 | 13 | #ifndef TASK_PUBLIC_H 14 | #define TASK_PUBLIC_H 15 | 16 | #ifdef __cplusplus 17 | extern "C" { 18 | #endif 19 | 20 | /**=======================================C头文件内容======================================**/ 21 | //任务句柄和任务函数声明 22 | //任务函数必须在此声明(在extern "C"块中),否则在app_freertos.c中找不到该函数符号 23 | void StartDebugTask(void *argument); 24 | void StartFOCTask(void *argument); 25 | void StartCommunicateTask(void *argument); 26 | void StartStartShell(void *argument); 27 | /**======================================================================================**/ 28 | 29 | #ifdef __cplusplus 30 | }; 31 | #endif 32 | 33 | #endif //TASK_PUBLIC_H 34 | -------------------------------------------------------------------------------- /BSP/retarget/retarget.h: -------------------------------------------------------------------------------- 1 | #ifndef _RETARGET_H__ 2 | #define _RETARGET_H__ 3 | 4 | #ifdef __cplusplus 5 | extern "C" { 6 | #endif 7 | 8 | #define USE_TinyPrintf 1 9 | 10 | #define STDIO_SUPPORT 1 11 | 12 | #include "stm32g4xx_hal.h" 13 | #include 14 | 15 | #if USE_TinyPrintf == 1 16 | 17 | #include "printf.h" 18 | 19 | #endif 20 | 21 | #if STDIO_SUPPORT == 1 22 | 23 | #include 24 | 25 | #endif 26 | 27 | #if STDIO_SUPPORT == 1 28 | 29 | int _isatty(int fd); 30 | 31 | int _write(int fd, char *ptr, int len); 32 | 33 | int _close(int fd); 34 | 35 | int _lseek(int fd, int ptr, int dir); 36 | 37 | int _read(int fd, char *ptr, int len); 38 | 39 | int _fstat(int fd, struct stat *st); 40 | 41 | #endif 42 | 43 | void CDC_Receive_FS_Callback(uint8_t *Buf, uint32_t *Len); 44 | void CDC_TransmitCplt_FS_Callback(); 45 | signed short shellRead(char *data, unsigned short len); 46 | signed short shellWrite(char *data, unsigned short len); 47 | 48 | #ifdef __cplusplus 49 | }; 50 | #endif 51 | 52 | #endif //#ifndef _RETARGET_H__ 53 | -------------------------------------------------------------------------------- /Doc/for_user.md: -------------------------------------------------------------------------------- 1 | ## 如何获得 2 | 3 | --- 4 | 5 | 1. **下载程序固件**:进入[Release](https://github.com/Liu-Curiousity/QDrive-Software/releases)页面,下载最新的固件文件( 6 | .bin、.hex或.elf文件)。 7 | 2. **准备驱动板**:从[此工程](https://github.com/Liu-Curiousity/QDrive-Hardware)准备QDrive驱动板,并组装完成。 8 | 3. **烧录固件**:使用STLink/JLink/DAPLink等编程器,将下载的固件烧录到QDrive驱动板上。可以使用STM32CubeProgrammer或其他支持的编程工具。 9 | 10 | - 烧录接口(hc0.8-4pin)位置如下图所示,注意线序(V:3.3V G:GND C:SWCLK D:SWDIO): 11 | 12 | ![](.\Doc\Images\SWD接口.png "SWD接口") 13 | 14 | ## 如何使用 15 | 16 | 适用于4310电机的QDrive具有以下两个接口:CAN总线、Type-C接口的USB串口。 17 | 18 | 下面是使用方法概要,更详细的使用说明、例程和注意事项参见[QD4310使用手册](https://pan.quark.cn/s/cfc4e3119ac5)。 19 | 20 | --- 21 | 22 | ### 首次上电 23 | 24 | 1. **连接电源**:在XT30(2+2)接口上连接7~26V电源为QDrive驱动板供电。 25 | 2. **连接电脑**:使用Type-C数据线将QDrive驱动板连接到计算机。 26 | 3. **打开串口工具**:QDrive的USB串口集成一个轻量化shell,使用串口工具(如PuTTY、MobaXTerm等)打开串口终端,波特率任意。 27 | 4. **新机校准**:首次使用时,需进行新机校准。输入`calibrate`命令,按提示操作完成校准。 28 | 29 | ### 后续使用 30 | 31 | 1. 可使用USB串口控制QDrive,串口输入`help`命令查看可用命令列表。 32 | 2. 可使用CAN总线控制QDrive,使用CAN总线发送相应的指令包:[QDrive CAN通信协议](../Applications/Src/CommunicationProtocol.md)。 -------------------------------------------------------------------------------- /Applications/Src/CommunicationProtocol.md: -------------------------------------------------------------------------------- 1 | # Qdrive CAN通信协议 2 | 3 | #### 波特率:`1Mbps` 4 | 5 | ## 控制报文 6 | 7 | - 报文地址`0x400+ID`,其中`ID`范围`0x0~0xF`,单次报文长度`3`bytes 8 | 9 | | bytes | 2-1 | 0 | 10 | |:-----:|:---:|:----:| 11 | | 说明 | 控制量 | 指令类型 | 12 | 13 | - 其中指令类型 14 | 15 | | 指令类型 | 0x00 | 0x01 | 0x02 | 0x03 | 0x04 | 0x05 | 0x06 | 16 | |:----:|:----------------:|:----:|:----:|:----:|:----:|:----:|------| 17 | | 说明 | NOP
用于获取反馈报文 | 使能 | 失能 | 电流控制 | 速度控制 | 角度控制 | 低速控制 | 18 | 19 | ## 反馈报文 20 | 21 | - 报文地址`0x500+ID`,单次报文长度`8`bytes 22 | - 当收到控制报文后,电机发送一次反馈报文 23 | 24 | | bytes | 7-6 | 5-4 | 3-2 | 1 | 0 | 25 | |:-----:|:----------------------:|:-------------------------:|:--------------------------:|:-------:|:----:| 26 | | 说明 | 角度 0~2pi
映射到uint16 | 转速 -1k~1krpm
映射到int16 | Q轴电流 -10A~10A
映射到int16 | 错误码(预留) | 电机状态 | 27 | 28 | - 其中电机状态 29 | 30 | | bit | 7 | 6 | 5 | 4 | 3 | 2 | 1 | 0 | 31 | |:---:|:--:|:--:|:--:|:--:|:--:|:--:|----|:---:| 32 | | 说明 | 预留 | 预留 | 预留 | 预留 | 预留 | 预留 | 预留 | 使能位 | -------------------------------------------------------------------------------- /BSP/Storage_EmbeddedFlash.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief Storage_EmbeddedFlash.h库文件 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 25-4-30 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于25-4-30 11 | * */ 12 | 13 | #ifndef STORAGE_EMBEDDEDFLASH_H 14 | #define STORAGE_EMBEDDEDFLASH_H 15 | 16 | #include "Storage.h" 17 | 18 | class Storage_EmbeddedFlash final : public Storage { 19 | public: 20 | bool initialized = false; 21 | 22 | void init() override { initialized = true; } 23 | 24 | void write(uint32_t addr, uint8_t *buff, uint32_t count) override; 25 | 26 | void read(uint32_t addr, uint8_t *buff, uint32_t count) override; 27 | 28 | private: 29 | /** 30 | * @brief 往页中写入数据 31 | * @param page 第几页 32 | * @param addr 当前页的相对地址 33 | * @param pdata 待写入数据 34 | * @param count 写入数据的长度 35 | */ 36 | static void write_page_bytes(uint32_t page, uint32_t addr, const uint8_t *pdata, uint32_t count); 37 | }; 38 | 39 | extern Storage_EmbeddedFlash storage; 40 | 41 | #endif //STORAGE_EMBEDDEDFLASH_H 42 | -------------------------------------------------------------------------------- /UserLib/FOC/base_classes/CurrentSensor.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief CurrentSensor base class 3 | * @detail User should override the pure virtual functions to implement the driver. 4 | * @author Haoqi Liu 5 | * @date 25-5-4 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于25-5-4 11 | * */ 12 | 13 | #ifndef CURRENTSENSOR_H 14 | #define CURRENTSENSOR_H 15 | 16 | class CurrentSensor { 17 | public: 18 | virtual ~CurrentSensor() = default; 19 | // user should define constructor self, just to assign the member variables. it should decouple from the hardware 20 | 21 | bool initialized = false; // true if the driver is initialized 22 | bool enabled = false; // true if the driver is enabled 23 | 24 | float iu, iv, iw; // current in u, v and w axis, units: A 25 | 26 | virtual void init() = 0; // initialize the driver 27 | virtual void enable() = 0; // enable the driver 28 | virtual void disable() = 0; // disable the driver 29 | 30 | // user should declare hardware specific parameters self 31 | }; 32 | 33 | #endif //CURRENTSENSOR_H 34 | -------------------------------------------------------------------------------- /UserLib/FOC/base_classes/Encoder.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief Encoder base class 3 | * @details User should override the pure virtual functions to implement the driver. 4 | * @author LiuHaoqi 5 | * @date 2025-4-8 6 | * @version V3.0.0 7 | * @note 8 | * @warning 9 | * @par history: 10 | V1.0.0 on 2024-7-3 11 | V2.0.0 on 2025-1-20,refactor by C++ 12 | V3.0.0 on 2025-4-8,redesign refer to SimpleFOC 13 | * */ 14 | 15 | #ifndef ENCODER_H 16 | #define ENCODER_H 17 | 18 | class Encoder { 19 | public: 20 | virtual ~Encoder() = default; 21 | // user should define constructor self, just to assign the member variables. it should decouple from the hardware 22 | 23 | bool initialized = false; // true if the driver is initialized 24 | bool enabled = false; // true if the driver is enabled 25 | 26 | virtual void init() = 0; // initialize the driver 27 | virtual void enable() = 0; // enable the driver 28 | virtual void disable() = 0; // disable the driver 29 | virtual float get_angle() =0; 30 | 31 | // user should declare hardware specific parameters self 32 | }; 33 | 34 | #endif //ENCODER_H 35 | -------------------------------------------------------------------------------- /UserLib/FOC/base_classes/Storage.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief a library for storage datas using embedded flash 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 25-4-22 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par history 10 | V1.0.0 on 25-4-22 11 | * */ 12 | 13 | #ifndef STORAGE_H 14 | #define STORAGE_H 15 | 16 | #include 17 | 18 | class Storage { 19 | public: 20 | virtual ~Storage() = default; 21 | // user should define constructor self, just to assign the member variables. it should decouple from the hardware 22 | 23 | bool initialized = false; 24 | 25 | virtual void init() = 0; 26 | 27 | /** 28 | * @brief 向储存区写入count个字节 29 | * @param addr 储存区地址(类似于VMA) 30 | * @param buff 写入缓冲区 31 | * @param count 写入字节数 32 | */ 33 | virtual void write(uint32_t addr, uint8_t *buff, uint32_t count) = 0; 34 | 35 | /** 36 | * @brief 从储存区读出count个字节 37 | * @param addr 储存区地址(类似于VMA) 38 | * @param buff 读出缓冲区 39 | * @param count 读取字节数 40 | */ 41 | virtual void read(uint32_t addr, uint8_t *buff, uint32_t count) = 0; 42 | }; 43 | 44 | #endif //STORAGE_H 45 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/LICENSE: -------------------------------------------------------------------------------- 1 | Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. 2 | Permission is hereby granted, free of charge, to any person obtaining a copy of 3 | this software and associated documentation files (the "Software"), to deal in 4 | the Software without restriction, including without limitation the rights to 5 | use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of 6 | the Software, and to permit persons to whom the Software is furnished to do so, 7 | subject to the following conditions: 8 | 9 | The above copyright notice and this permission notice shall be included in all 10 | copies or substantial portions of the Software. 11 | 12 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 13 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS 14 | FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR 15 | COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER 16 | IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN 17 | CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. 18 | 19 | -------------------------------------------------------------------------------- /Applications/Shell/StartShell.cpp: -------------------------------------------------------------------------------- 1 | #include "task_public.h" 2 | #include "usbd_cdc_if.h" 3 | #include "usb_device.h" 4 | #include "shell_cpp.h" 5 | #include "retarget/retarget.h" 6 | #include "task.h" 7 | 8 | Shell shell; 9 | char shellBuffer[256]; 10 | 11 | void USB_Disconnected() { 12 | __HAL_RCC_USB_FORCE_RESET(); 13 | HAL_Delay(200); 14 | __HAL_RCC_USB_RELEASE_RESET(); 15 | 16 | GPIO_InitTypeDef GPIO_Initure; 17 | __HAL_RCC_GPIOA_CLK_ENABLE(); 18 | 19 | GPIO_Initure.Pin = GPIO_PIN_11 | GPIO_PIN_12; 20 | GPIO_Initure.Mode = GPIO_MODE_OUTPUT_PP; 21 | GPIO_Initure.Pull = GPIO_PULLDOWN; 22 | GPIO_Initure.Speed = GPIO_SPEED_FREQ_HIGH; 23 | HAL_GPIO_Init(GPIOA, &GPIO_Initure); 24 | 25 | HAL_GPIO_WritePin(GPIOA, GPIO_PIN_11, GPIO_PIN_RESET); 26 | HAL_GPIO_WritePin(GPIOA, GPIO_PIN_12, GPIO_PIN_RESET); 27 | HAL_Delay(300); 28 | } 29 | 30 | void StartStartShell(void *argument) { 31 | USB_Disconnected(); //USB重枚举 32 | MX_USB_Device_Init(); 33 | delay(100); // 错开RAM使用高峰期 34 | shell.read = shellRead; 35 | shell.write = shellWrite; 36 | shellInit(&shell, shellBuffer, 256); 37 | xTaskCreate(shellTask, "LetterShellTask", 128, &shell, osPriorityNormal, nullptr); 38 | vTaskDelete(nullptr); 39 | } 40 | -------------------------------------------------------------------------------- /UserLib/FOC/base_classes/BLDC_Driver.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief BLDC_Driver base class 3 | * @details User should override the pure virtual functions to implement the driver. 4 | * @author LiuHaoqi 5 | * @date 2025-4-8 6 | * @version V3.0.0 7 | * @note 8 | * @warning 9 | * @par history: 10 | V1.0.0 on 2024-5-12 11 | V2.0.0 on 2025-1-20,refactor by C++ 12 | V3.0.0 on 2025-4-8,redesign refer to SimpleFOC 13 | * */ 14 | 15 | #ifndef BLDC_DRIVER_H 16 | #define BLDC_DRIVER_H 17 | 18 | class BLDC_Driver { 19 | public: 20 | virtual ~BLDC_Driver() = default; 21 | // user should define constructor self, just to assign the member variables. it should decouple from the hardware 22 | 23 | bool initialized = false; // true if the driver is initialized 24 | bool enabled = false; // true if the driver is enabled 25 | 26 | virtual void init() = 0; // initialize the driver 27 | virtual void enable() = 0; // enable the driver 28 | virtual void disable() = 0; // disable the driver 29 | 30 | // set the duty cycle of the driver, then Uu Uv Uw is equal to Vbus * duty 31 | // the duty cycle is normalized to [0, 1] 32 | virtual void set_duty(float u, float v, float w) = 0; 33 | 34 | // user should declare hardware specific parameters self 35 | }; 36 | 37 | #endif //BLDC_DRIVER_H 38 | -------------------------------------------------------------------------------- /BSP/retarget/CharCircularQueue.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief CharCircularQueue库文件 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 2025/6/22 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于2025/6/22 11 | * */ 12 | 13 | #pragma once 14 | 15 | class CharCircularQueue { 16 | public: 17 | // 构造函数:动态指定容量 18 | explicit CharCircularQueue(const int capacity) : 19 | size(capacity), head(0), tail(0), count(0) { 20 | buf = new char[size]; 21 | } 22 | 23 | ~CharCircularQueue() { 24 | delete[] buf; 25 | } 26 | 27 | [[nodiscard]] bool isEmpty() const { return count == 0; } 28 | [[nodiscard]] bool isFull() const { return count == size; } 29 | 30 | bool enqueue(char c) { 31 | if (isFull()) return false; 32 | buf[tail] = c; 33 | tail = (tail + 1) % size; 34 | ++count; 35 | return true; 36 | } 37 | 38 | bool dequeue(char& c) { 39 | if (isEmpty()) return false; 40 | c = buf[head]; 41 | head = (head + 1) % size; 42 | --count; 43 | return true; 44 | } 45 | 46 | [[nodiscard]] char front() const { return buf[head]; } 47 | [[nodiscard]] int Size() const { return size; } 48 | [[nodiscard]] int currentSize() const { return count; } 49 | 50 | private: 51 | char *buf; 52 | int size; 53 | int head; 54 | int tail; 55 | int count; 56 | }; 57 | -------------------------------------------------------------------------------- /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) 2024 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 | -------------------------------------------------------------------------------- /Applications/Inc/FOC_config.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief 用于定义FOC控制器的配置常量 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 25-5-5 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于25-5-5 11 | * */ 12 | 13 | #ifndef FOC_CONFIG_H 14 | #define FOC_CONFIG_H 15 | 16 | #define FOC_HARDWARE_VERSION "4310_5.1.0" 17 | #define FOC_SOFTWARE_VERSION "5.1.4" 18 | 19 | /*==========================电机参数==========================*/ 20 | #define FOC_KV 33.0f // KV值,单位rpm/V 21 | #define FOC_POLE_PAIRS 14 // 极对数 22 | #define FOC_NOMINAL_VOLTAGE 24 // 额定电压,单位V 23 | #define FOC_PHASE_INDUCTANCE 4.74f // 相电感,单位mH 24 | #define FOC_PHASE_RESISTANCE 10.9f // 相电阻,单位Ω 25 | #define FOC_TORQUE_CONSTANT 0.27f // 转矩常数,单位Nm/A 26 | 27 | /*=========================驱动板参数==========================*/ 28 | #define FOC_MAX_CURRENT 1.65f // 最大电流,单位A 29 | 30 | /*==========================配置参数==========================*/ 31 | #define FOC_MAX_SPEED 1000.0f // 最大转速,单位rpm 32 | 33 | #define FOC_CURRENT_KP 10.0f 34 | #define FOC_CURRENT_KI 1.0f 35 | #define FOC_CURRENT_KD 0.0f 36 | #define FOC_SPEED_KP 3e-3f 37 | #define FOC_SPEED_KI 3.9e-4f 38 | #define FOC_SPEED_KD 0.0f 39 | #define FOC_ANGLE_KP 1200.0f 40 | #define FOC_ANGLE_KI 0.0f 41 | #define FOC_ANGLE_KD 0.0f 42 | 43 | #endif //FOC_CONFIG_H 44 | -------------------------------------------------------------------------------- /UserLib/LetterShell/Inc/shell_ext.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file shell_ext.h 3 | * @author Letter (NevermindZZT@gmail.com) 4 | * @brief shell extensions 5 | * @version 3.0.0 6 | * @date 2019-12-31 7 | * 8 | * @copyright (c) 2019 Letter 9 | * 10 | */ 11 | 12 | #ifndef __SHELL_EXT_H__ 13 | #define __SHELL_EXT_H__ 14 | 15 | #include "shell.h" 16 | 17 | /** 18 | * @brief 数字类型 19 | * 20 | */ 21 | typedef enum 22 | { 23 | NUM_TYPE_DEC, /**< 十进制整型 */ 24 | NUM_TYPE_BIN, /**< 二进制整型 */ 25 | NUM_TYPE_OCT, /**< 八进制整型 */ 26 | NUM_TYPE_HEX, /**< 十六进制整型 */ 27 | NUM_TYPE_FLOAT /**< 浮点型 */ 28 | } ShellNumType; 29 | 30 | #if SHELL_SUPPORT_ARRAY_PARAM == 1 31 | typedef struct 32 | { 33 | unsigned short size; 34 | unsigned char elementBytes; 35 | } ShellArrayHeader; 36 | #endif /** SHELL_SUPPORT_ARRAY_PARAM == 1 */ 37 | 38 | int shellExtParsePara(Shell *shell, char *string, char *type, size_t *result); 39 | #if SHELL_USING_FUNC_SIGNATURE == 1 40 | int shellExtCleanerPara(Shell *shell, char *type, size_t param); 41 | #endif /** SHELL_USING_FUNC_SIGNATURE == 1 */ 42 | #if SHELL_SUPPORT_ARRAY_PARAM == 1 43 | int shellGetArrayParamSize(void *param); 44 | #endif /** SHELL_SUPPORT_ARRAY_PARAM == 1 */ 45 | int shellExtRun(Shell *shell, ShellCommand *command, int argc, char *argv[]); 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /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) 2024 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 | -------------------------------------------------------------------------------- /Core/Inc/fdcan.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file fdcan.h 5 | * @brief This file contains all the function prototypes for 6 | * the fdcan.c file 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2024 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 __FDCAN_H__ 22 | #define __FDCAN_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 FDCAN_HandleTypeDef hfdcan1; 36 | 37 | /* USER CODE BEGIN Private defines */ 38 | 39 | /* USER CODE END Private defines */ 40 | 41 | void MX_FDCAN1_Init(void); 42 | 43 | /* USER CODE BEGIN Prototypes */ 44 | 45 | /* USER CODE END Prototypes */ 46 | 47 | #ifdef __cplusplus 48 | } 49 | #endif 50 | 51 | #endif /* __FDCAN_H__ */ 52 | 53 | -------------------------------------------------------------------------------- /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) 2024 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 | extern ADC_HandleTypeDef hadc2; 38 | 39 | /* USER CODE BEGIN Private defines */ 40 | 41 | /* USER CODE END Private defines */ 42 | 43 | void MX_ADC1_Init(void); 44 | void MX_ADC2_Init(void); 45 | 46 | /* USER CODE BEGIN Prototypes */ 47 | 48 | /* USER CODE END Prototypes */ 49 | 50 | #ifdef __cplusplus 51 | } 52 | #endif 53 | 54 | #endif /* __ADC_H__ */ 55 | 56 | -------------------------------------------------------------------------------- /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) 2024 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 | extern TIM_HandleTypeDef htim6; 38 | 39 | /* USER CODE BEGIN Private defines */ 40 | 41 | /* USER CODE END Private defines */ 42 | 43 | void MX_TIM1_Init(void); 44 | void MX_TIM6_Init(void); 45 | 46 | void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim); 47 | 48 | /* USER CODE BEGIN Prototypes */ 49 | 50 | /* USER CODE END Prototypes */ 51 | 52 | #ifdef __cplusplus 53 | } 54 | #endif 55 | 56 | #endif /* __TIM_H__ */ 57 | 58 | -------------------------------------------------------------------------------- /UserLib/FOC/base_classes/Filter.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief Filter base class 3 | * @details User should override the pure virtual functions to implement the driver. 4 | * @author LiuHaoqi 5 | * @date 2025-4-11 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par history: 10 | V1.0.0 on 2025-4-11 11 | * */ 12 | 13 | #ifndef FILTER_H 14 | #define FILTER_H 15 | 16 | class Filter { 17 | public: 18 | virtual ~Filter() = default; 19 | // user should define constructor self, just to assign the member variables. 20 | 21 | virtual float getTs() = 0; //!< Return filter time constant 22 | virtual float operator()(float x) = 0; 23 | }; 24 | 25 | class LP_Filter : public Filter { 26 | public: 27 | virtual float getFc() = 0; //!< Return filter cut-off frequency, unit s 28 | }; 29 | 30 | class HP_Filter : public Filter { 31 | public: 32 | virtual float getFc() = 0; //!< Return filter cut-off frequency, unit s 33 | }; 34 | 35 | class BP_Filter : public Filter { 36 | public: 37 | virtual float getFp() = 0; //!< Return filter cut-off frequency, unit s 38 | virtual float getFs() = 0; //!< Return filter cut-off frequency, unit s 39 | float getBW() { return getFs() - getFp(); } //!< Return filter bandwidth, unit s 40 | }; 41 | 42 | class BS_Filter : public Filter { 43 | public: 44 | virtual float getFp() = 0; //!< Return filter cut-off frequency, unit s 45 | virtual float getFs() = 0; //!< Return filter cut-off frequency, unit s 46 | float getBW() { return getFp() - getFs(); } //!< Return filter bandwidth, unit s 47 | }; 48 | 49 | #endif //FILTER_H 50 | -------------------------------------------------------------------------------- /CMakePresets.json: -------------------------------------------------------------------------------- 1 | { 2 | "version": 3, 3 | "configurePresets": [ 4 | { 5 | "name": "default", 6 | "hidden": true, 7 | "generator": "Ninja", 8 | "binaryDir": "${sourceDir}/build/${presetName}", 9 | "toolchainFile": "${sourceDir}/cmake/gcc-arm-none-eabi.cmake", 10 | "cacheVariables": { 11 | } 12 | }, 13 | { 14 | "name": "Debug", 15 | "inherits": "default", 16 | "cacheVariables": { 17 | "CMAKE_BUILD_TYPE": "Debug" 18 | } 19 | }, 20 | { 21 | "name": "RelWithDebInfo", 22 | "inherits": "default", 23 | "cacheVariables": { 24 | "CMAKE_BUILD_TYPE": "RelWithDebInfo" 25 | } 26 | }, 27 | { 28 | "name": "Release", 29 | "inherits": "default", 30 | "cacheVariables": { 31 | "CMAKE_BUILD_TYPE": "Release" 32 | } 33 | }, 34 | { 35 | "name": "MinSizeRel", 36 | "inherits": "default", 37 | "cacheVariables": { 38 | "CMAKE_BUILD_TYPE": "MinSizeRel" 39 | } 40 | } 41 | ], 42 | "buildPresets": [ 43 | { 44 | "name": "Debug", 45 | "configurePreset": "Debug" 46 | }, 47 | { 48 | "name": "RelWithDebInfo", 49 | "configurePreset": "RelWithDebInfo" 50 | }, 51 | { 52 | "name": "Release", 53 | "configurePreset": "Release" 54 | }, 55 | { 56 | "name": "MinSizeRel", 57 | "configurePreset": "MinSizeRel" 58 | } 59 | ] 60 | } -------------------------------------------------------------------------------- /BSP/CurrentSensor_Embed.h: -------------------------------------------------------------------------------- 1 | // 2 | // Created by 26757 on 25-5-4. 3 | // 4 | #pragma once 5 | 6 | #include "CurrentSensor.h" 7 | #include "adc.h" 8 | 9 | class CurrentSensor_Embed final : public CurrentSensor { 10 | public: 11 | CurrentSensor_Embed(ADC_HandleTypeDef *hadc1, ADC_HandleTypeDef *hadc2) : 12 | hadc1(hadc1), hadc2(hadc2) {} 13 | 14 | void init() override { 15 | HAL_ADCEx_Calibration_Start(hadc1, ADC_SINGLE_ENDED); //校准ADC 16 | HAL_ADCEx_Calibration_Start(hadc2, ADC_SINGLE_ENDED); //校准ADC 17 | initialized = true; 18 | } 19 | 20 | void enable() override { 21 | ADC_Enable(hadc1); 22 | ADC_Enable(hadc2); 23 | HAL_ADCEx_InjectedStart_IT(hadc1); //开启ADC采样 24 | enabled = true; 25 | } 26 | 27 | void disable() override { 28 | ADC_Disable(hadc1); 29 | ADC_Disable(hadc2); 30 | HAL_ADCEx_InjectedStop_IT(hadc1); //开启ADC采样 31 | enabled = false; 32 | } 33 | 34 | void update() { 35 | static constexpr float V_REF = 3.3f; // ADC基准电压,单位:V 36 | static constexpr float ADC_REVOLUTION = 4096 - 1; // ADC分辨率 37 | static constexpr float OP_AMP_GAIN = 20.0f; // 差分运放电压增益,单位:V/V 38 | static constexpr float R_SENSE = 0.05f; // 采样电阻阻值,单位:Ω 39 | 40 | const float iu = 2048 - static_cast(hadc2->Instance->JDR1); 41 | this->iu = iu / ADC_REVOLUTION * V_REF / OP_AMP_GAIN / R_SENSE; 42 | const float iv = static_cast(hadc1->Instance->JDR1) - 2048; 43 | this->iv = iv / ADC_REVOLUTION * V_REF / OP_AMP_GAIN / R_SENSE; 44 | this->iw = -(this->iu + this->iv); 45 | }; 46 | 47 | private: 48 | ADC_HandleTypeDef *hadc1; 49 | ADC_HandleTypeDef *hadc2; 50 | }; 51 | -------------------------------------------------------------------------------- /UserLib/FOC/readme.md: -------------------------------------------------------------------------------- 1 | # QDrive 使用手册 2 | 3 | ## FOC类接口 4 | 5 | - CtrlType: 控制类型 6 | - speed(): 获取电机转速,单位rpm 7 | - angle(): 获取电机角度,单位rad 8 | - current(): 获取Q轴电流,单位A 9 | - voltage(): 获取母线电压,单位V 10 | 11 | 12 | - calibrate(): FOC基础校准,包括:校准偏置电流,测量相电阻,校准编码器方向,校准电角度 13 | - anticogging_calibrate(): 校准反齿轮效应 14 | 15 | 16 | - init(): 初始化FOC类 17 | - enable(): 使能FOC控制 18 | - disable(): 失能FOC控制 19 | - start(): 启动FOC控制 20 | - stop(): 停止FOC控制 21 | 22 | - Ctrl(): 外部控制调用接口 23 | - Ctrl_ISR(): FOC(位置环,速度环)控制中断服务函数 24 | - loopCtrl(): FOC(电流环)控制中断服务函数 25 | - updateVoltage(): 更新母线电压 26 | 27 | - pole_pairs: 电机极对数 28 | - CtrlFrequency: 控制频率,单位Hz 29 | - CurrentCtrlFrequency: 电流环控制频率,单位Hz 30 | 31 | - initialized: FOC类是否已初始化 32 | - enabled: FOC控制是否已使能 33 | - started: FOC控制是否已启动 34 | - calibrated: FOC类是否已校准 35 | - anticogging_enabled: FOC反齿轮效应校准是否已启用 36 | - anticogging_calibrated: FOC反齿轮效应校准是否已完成 37 | 38 | ## QDrive 启动流程概述 39 | 40 | 1. 构造FOC类对象 41 | - 配置电机参数: pole_pairs 42 | - 配置控制频率: CtrlFrequency, CurrentCtrlFrequency 43 | - 配置滤波器: CurrentFilter,SpeedFilter 44 | - 配置硬件接口: BLDC驱动,编码器,储存器,电流传感器 45 | - 配置PID参数: CurrentPID, SpeedPID, PositionPID 46 | 2. 调用init()函数进行初始化 47 | - 完成init()初始化后,FOC其他函数才能正常使用 48 | 3. 调用enable()函数使能FOC控制 49 | - 完成enable()使能后,FOC控制器开始工作,驱动启动,电机状态开始更新(如果已校准) 50 | 4. 调用calibrate()函数进行FOC基础校准(若未校准) 51 | - 完成calibrate()校准后,FOC控制器可以正常工作,电机状态开始更新 52 | 5. 调用anticogging_calibrate()函数进行FOC基础校准(若未校准) 53 | - 完成anticogging_calibrate()校准后,可以启用齿槽转矩补偿功能 54 | - 需要先完成calibrate()基础校准 55 | 6. 调用start()函数启动FOC控制 56 | 57 | ### 依赖关系 58 | 59 | - init(): 完成类构造 60 | - enable(): 完成init()初始化 61 | - start(): 完成enable()使能, 完成calibrate()校准 62 | - calibrate(): 完成enable()使能, 未调用start()启动 63 | - anticogging_calibrate(): 完成enable()使能, 未调用start()启动, 完成calibrate()校准 64 | - 更新电机状态(电流,转速,角度): 完成enable()使能, 完成calibrate()校准 -------------------------------------------------------------------------------- /Drivers/CMSIS/Include/cmsis_version.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file cmsis_version.h 3 | * @brief CMSIS Core(M) Version definitions 4 | * @version V5.0.3 5 | * @date 24. June 2019 6 | ******************************************************************************/ 7 | /* 8 | * Copyright (c) 2009-2019 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 ( 3U) /*!< [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 | -------------------------------------------------------------------------------- /BSP/retarget/CDC_Tx_DualBuffer.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief CDC_Tx_DualBuffer.h库文件 3 | * @detail 4 | * @author Haoqi Liu 5 | * @date 2025/9/11 6 | * @version V1.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | V1.0.0创建于2025/9/11 11 | * */ 12 | 13 | #pragma once 14 | 15 | #include 16 | 17 | template 18 | class TxDualBuffer { 19 | public: 20 | explicit TxDualBuffer(uint8_t (*TxFunc)(uint8_t *, uint16_t)) : TxFunc(TxFunc) {}; 21 | 22 | [[nodiscard]] bool isTransmitting() const { return transmitting; } 23 | 24 | bool inBuffer(Tp *& buf, std::size_t len) { 25 | static bool result = false; 26 | HAL_NVIC_DisableIRQ(USB_LP_IRQn); 27 | if (Nm - buffer_index >= len) { 28 | std::copy(buf, buf + len, vice_buffer + buffer_index); 29 | buffer_index += len; 30 | result = true; 31 | } else { 32 | result = false; 33 | } 34 | // if (buffer_index && !transmitting) start_transmit(); 35 | if (buffer_index) start_transmit(); // 原本是要判断transmitting的,但是该死的CDC,发送失败是不会有回调函数的,故只能这样写了 36 | HAL_NVIC_EnableIRQ(USB_LP_IRQn); 37 | return result; 38 | } 39 | 40 | void transmitComplete() { 41 | if (buffer_index) start_transmit(); 42 | else transmitting = false; 43 | } 44 | 45 | private: 46 | Tp buffer1[Nm]{}; 47 | Tp buffer2[Nm]{}; 48 | Tp *main_buffer{buffer1}; 49 | Tp *vice_buffer{buffer2}; 50 | size_t buffer_index{0}; 51 | bool transmitting{false}; 52 | uint8_t (*TxFunc)(uint8_t *, uint16_t); 53 | 54 | void start_transmit() { 55 | if (TxFunc(reinterpret_cast(vice_buffer), buffer_index) == 0) { 56 | std::swap(main_buffer, vice_buffer); 57 | buffer_index = 0; 58 | transmitting = true; 59 | } else { 60 | transmitting = false; 61 | } 62 | } 63 | }; -------------------------------------------------------------------------------- /BSP/Encoder_MT6825.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief Encoder MT6825 Version 3 | * @details 4 | * @author Haoqi Liu 5 | * @date 2025-4-16 6 | * @version V3.0.0 7 | * @note 8 | * @warning 9 | * @par 历史版本: 10 | V1.0.0创建于2024-7-3 11 | V2.0.0 on 2025-1-20,refactor by C++ 12 | V3.0.0 on 2025-4-16,delete ZeroPosition_Calibration and put it in FOC Class 13 | * */ 14 | 15 | #ifndef ENCODER_DRIVER_MT6825_H 16 | #define ENCODER_DRIVER_MT6825_H 17 | 18 | #include 19 | #include "Encoder.h" 20 | #include "spi.h" 21 | #include "gpio.h" 22 | 23 | class Encoder_MT6825 final : public Encoder { 24 | public: 25 | ~Encoder_MT6825() override = default; 26 | 27 | Encoder_MT6825(GPIO_TypeDef *CS_GPIO_Port, 28 | const uint16_t CS_GPIO_Pin, 29 | SPI_HandleTypeDef *hspi): 30 | hspi(hspi), 31 | CS_GPIO_Port(CS_GPIO_Port), 32 | CS_GPIO_Pin(CS_GPIO_Pin) {} 33 | 34 | void init() override { 35 | static uint8_t txData = 0x83; 36 | HAL_GPIO_WritePin(CS_GPIO_Port, CS_GPIO_Pin, GPIO_PIN_SET); 37 | HAL_SPI_Transmit(hspi, &txData, 1, HAL_MAX_DELAY); // 这句必须加,不然CSn片选时MOSI还是高电平 38 | HAL_GPIO_WritePin(CS_GPIO_Port, CS_GPIO_Pin, GPIO_PIN_RESET); 39 | HAL_SPI_Transmit(hspi, &txData, 1, HAL_MAX_DELAY); 40 | initialized = true; 41 | } 42 | 43 | void enable() override { 44 | if (!initialized) return; 45 | enabled = true; 46 | } 47 | 48 | void disable() override { 49 | if (!initialized) return; 50 | enabled = false; 51 | } 52 | 53 | float get_angle() override { 54 | static uint8_t rxData[3]{}; 55 | if (!enabled) return 0; 56 | HAL_SPI_Receive(hspi, rxData, 3,HAL_MAX_DELAY); 57 | return (rxData[0] << 10 | (rxData[1] & 0xFC) << 2 | rxData[2] >> 4) / 262144.0f 58 | * 2 * std::numbers::pi_v; 59 | } 60 | 61 | private: 62 | SPI_HandleTypeDef *hspi = nullptr; 63 | GPIO_TypeDef *CS_GPIO_Port = nullptr; 64 | uint16_t CS_GPIO_Pin = 0; 65 | }; 66 | 67 | #endif //ENCODER_DRIVER_MT6825_H 68 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_spi_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32g4xx_hal_spi_ex.h 4 | * @author MCD Application Team 5 | * @brief Header file of SPI HAL Extended module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2019 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 | 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef STM32G4xx_HAL_SPI_EX_H 21 | #define STM32G4xx_HAL_SPI_EX_H 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "stm32g4xx_hal_def.h" 29 | 30 | /** @addtogroup STM32G4xx_HAL_Driver 31 | * @{ 32 | */ 33 | 34 | /** @addtogroup SPIEx 35 | * @{ 36 | */ 37 | 38 | /* Exported types ------------------------------------------------------------*/ 39 | /* Exported constants --------------------------------------------------------*/ 40 | /* Exported macros -----------------------------------------------------------*/ 41 | /* Exported functions --------------------------------------------------------*/ 42 | /** @addtogroup SPIEx_Exported_Functions 43 | * @{ 44 | */ 45 | 46 | /* Initialization and de-initialization functions ****************************/ 47 | /* IO operation functions *****************************************************/ 48 | /** @addtogroup SPIEx_Exported_Functions_Group1 49 | * @{ 50 | */ 51 | HAL_StatusTypeDef HAL_SPIEx_FlushRxFifo(const SPI_HandleTypeDef *hspi); 52 | /** 53 | * @} 54 | */ 55 | 56 | /** 57 | * @} 58 | */ 59 | 60 | /** 61 | * @} 62 | */ 63 | 64 | /** 65 | * @} 66 | */ 67 | 68 | #ifdef __cplusplus 69 | } 70 | #endif 71 | 72 | #endif /* STM32G4xx_HAL_SPI_EX_H */ 73 | 74 | -------------------------------------------------------------------------------- /cmake/gcc-arm-none-eabi.cmake: -------------------------------------------------------------------------------- 1 | set(CMAKE_SYSTEM_NAME Generic) 2 | set(CMAKE_SYSTEM_PROCESSOR arm) 3 | 4 | set(CMAKE_C_COMPILER_FORCED TRUE) 5 | set(CMAKE_CXX_COMPILER_FORCED TRUE) 6 | set(CMAKE_C_COMPILER_ID GNU) 7 | set(CMAKE_CXX_COMPILER_ID GNU) 8 | 9 | # Some default GCC settings 10 | # arm-none-eabi- must be part of path environment 11 | set(TOOLCHAIN_PREFIX arm-none-eabi-) 12 | 13 | set(CMAKE_C_COMPILER ${TOOLCHAIN_PREFIX}gcc) 14 | set(CMAKE_ASM_COMPILER ${CMAKE_C_COMPILER}) 15 | set(CMAKE_CXX_COMPILER ${TOOLCHAIN_PREFIX}g++) 16 | set(CMAKE_LINKER ${TOOLCHAIN_PREFIX}g++) 17 | set(CMAKE_OBJCOPY ${TOOLCHAIN_PREFIX}objcopy) 18 | set(CMAKE_SIZE ${TOOLCHAIN_PREFIX}size) 19 | 20 | set(CMAKE_EXECUTABLE_SUFFIX_ASM ".elf") 21 | set(CMAKE_EXECUTABLE_SUFFIX_C ".elf") 22 | set(CMAKE_EXECUTABLE_SUFFIX_CXX ".elf") 23 | 24 | set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) 25 | 26 | # MCU specific flags 27 | set(TARGET_FLAGS "-mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard ") 28 | 29 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${TARGET_FLAGS}") 30 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra -Wpedantic -fdata-sections -ffunction-sections") 31 | if(CMAKE_BUILD_TYPE MATCHES Debug) 32 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Og -g3") 33 | endif() 34 | if(CMAKE_BUILD_TYPE MATCHES Release) 35 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Os -g0") 36 | endif() 37 | 38 | set(CMAKE_ASM_FLAGS "${CMAKE_C_FLAGS} -x assembler-with-cpp -MMD -MP") 39 | set(CMAKE_CXX_FLAGS "${CMAKE_C_FLAGS} -fno-rtti -fno-exceptions -fno-threadsafe-statics") 40 | 41 | set(CMAKE_C_LINK_FLAGS "${TARGET_FLAGS}") 42 | set(CMAKE_C_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} -T \"${CMAKE_SOURCE_DIR}/STM32G431XX_FLASH.ld\"") 43 | set(CMAKE_C_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} --specs=nano.specs") 44 | set(CMAKE_C_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} -Wl,-Map=${CMAKE_PROJECT_NAME}.map -Wl,--gc-sections") 45 | set(CMAKE_C_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} -Wl,--start-group -lc -lm -Wl,--end-group") 46 | set(CMAKE_C_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} -Wl,--print-memory-usage") 47 | 48 | set(CMAKE_CXX_LINK_FLAGS "${CMAKE_C_LINK_FLAGS} -Wl,--start-group -lstdc++ -lsupc++ -Wl,--end-group") -------------------------------------------------------------------------------- /Core/Inc/stm32g4xx_it.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32g4xx_it.h 5 | * @brief This file contains the headers of the interrupt handlers. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2024 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 __STM32G4xx_IT_H 22 | #define __STM32G4xx_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 SysTick_Handler(void); 56 | void ADC1_2_IRQHandler(void); 57 | void USB_LP_IRQHandler(void); 58 | void FDCAN1_IT0_IRQHandler(void); 59 | void FDCAN1_IT1_IRQHandler(void); 60 | void TIM6_DAC_IRQHandler(void); 61 | /* USER CODE BEGIN EFP */ 62 | 63 | /* USER CODE END EFP */ 64 | 65 | #ifdef __cplusplus 66 | } 67 | #endif 68 | 69 | #endif /* __STM32G4xx_IT_H */ 70 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ramfunc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32g4xx_hal_flash_ramfunc.h 4 | * @author MCD Application Team 5 | * @brief Header file of FLASH RAMFUNC driver. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2019 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file in 13 | * 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 19 | #ifndef STM32G4xx_FLASH_RAMFUNC_H 20 | #define STM32G4xx_FLASH_RAMFUNC_H 21 | 22 | #ifdef __cplusplus 23 | extern "C" { 24 | #endif 25 | 26 | /* Includes ------------------------------------------------------------------*/ 27 | #include "stm32g4xx_hal_def.h" 28 | 29 | /** @addtogroup STM32G4xx_HAL_Driver 30 | * @{ 31 | */ 32 | 33 | /** @addtogroup FLASH_RAMFUNC 34 | * @{ 35 | */ 36 | 37 | /* Exported types ------------------------------------------------------------*/ 38 | /* Exported macro ------------------------------------------------------------*/ 39 | /* Exported functions --------------------------------------------------------*/ 40 | /** @addtogroup FLASH_RAMFUNC_Exported_Functions 41 | * @{ 42 | */ 43 | 44 | /** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1 45 | * @{ 46 | */ 47 | /* Peripheral Control functions ************************************************/ 48 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableRunPowerDown(void); 49 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableRunPowerDown(void); 50 | #if defined (FLASH_OPTR_DBANK) 51 | __RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_OB_DBankConfig(uint32_t DBankConfig); 52 | #endif 53 | /** 54 | * @} 55 | */ 56 | 57 | /** 58 | * @} 59 | */ 60 | 61 | /** 62 | * @} 63 | */ 64 | 65 | /** 66 | * @} 67 | */ 68 | 69 | #ifdef __cplusplus 70 | } 71 | #endif 72 | 73 | #endif /* STM32G4xx_FLASH_RAMFUNC_H */ 74 | 75 | -------------------------------------------------------------------------------- /UserLib/LetterShell/Src/shell_companion.c: -------------------------------------------------------------------------------- 1 | /** 2 | * @file shell_companion.c 3 | * @author Letter (nevermindzzt@gmail.com) 4 | * @brief shell companion object support 5 | * @version 3.0.3 6 | * @date 2020-07-22 7 | * 8 | * @copyright (c) 2020 Letter 9 | * 10 | */ 11 | #include "shell.h" 12 | 13 | #if SHELL_USING_COMPANION == 1 14 | /** 15 | * @brief shell添加伴生对象 16 | * 17 | * @param shell shell对象 18 | * @param id 伴生对象ID 19 | * @param object 伴生对象 20 | * @return signed char 0 添加成功 -1 添加失败 21 | */ 22 | signed char shellCompanionAdd(Shell *shell, int id, void *object) 23 | { 24 | ShellCompanionObj *companions = shell->info.companions; 25 | ShellCompanionObj *node = SHELL_MALLOC(sizeof(ShellCompanionObj)); 26 | SHELL_ASSERT(node, return -1); 27 | node->id = id; 28 | node->obj = object; 29 | node->next = companions; 30 | shell->info.companions = node; 31 | return 0; 32 | } 33 | 34 | /** 35 | * @brief shell删除伴生对象 36 | * 37 | * @param shell shell对象 38 | * @param id 伴生对象ID 39 | * @return signed char 0 删除成功 -1 无匹配对象 40 | */ 41 | signed char shellCompanionDel(Shell *shell, int id) 42 | { 43 | ShellCompanionObj *companions = shell->info.companions; 44 | ShellCompanionObj *front = companions; 45 | while (companions) 46 | { 47 | if (companions->id == id) 48 | { 49 | if (companions == shell->info.companions && !(companions->next)) 50 | { 51 | shell->info.companions = (void *)0; 52 | } 53 | else 54 | { 55 | front->next = companions->next; 56 | } 57 | SHELL_FREE(companions); 58 | return 0; 59 | } 60 | front = companions; 61 | companions = companions->next; 62 | } 63 | return -1; 64 | } 65 | 66 | /** 67 | * @brief shell获取伴生对象 68 | * 69 | * @param shell shell对象 70 | * @param id 伴生对象ID 71 | * @return void* 伴生对象,无匹配对象时返回NULL 72 | */ 73 | void *shellCompanionGet(Shell *shell, int id) 74 | { 75 | SHELL_ASSERT(shell, return (void *)0); 76 | ShellCompanionObj *companions = shell->info.companions; 77 | while (companions) 78 | { 79 | if (companions->id == id) 80 | { 81 | return companions->obj; 82 | } 83 | companions = companions->next; 84 | } 85 | return (void *)0; 86 | } 87 | #endif /** SHELL_USING_COMPANION == 1 */ 88 | -------------------------------------------------------------------------------- /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) 2024 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 "stm32g4xx_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 LED_G_Pin GPIO_PIN_0 61 | #define LED_G_GPIO_Port GPIOF 62 | #define LED_R_Pin GPIO_PIN_1 63 | #define LED_R_GPIO_Port GPIOF 64 | #define SPI1_CSn_Pin GPIO_PIN_4 65 | #define SPI1_CSn_GPIO_Port GPIOC 66 | 67 | /* USER CODE BEGIN Private defines */ 68 | 69 | /* USER CODE END Private defines */ 70 | 71 | #ifdef __cplusplus 72 | } 73 | #endif 74 | 75 | #endif /* __MAIN_H */ 76 | -------------------------------------------------------------------------------- /BSP/BLDC_Driver_FD6288.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief BLDC_Driver base class 3 | * @details BLDC驱动库封装并提供以下接口: 4 | * start() 启动BLDC驱动 5 | * stop() 关闭BLDC驱动 6 | * set_duty() 设置BLDC三相占空比,归一化 7 | * @author LiuHaoqi 8 | * @date 2025-4-8 9 | * @version V3.0.0 10 | * @note 11 | * @warning 12 | * @par history: 13 | V1.0.0 on 2024-5-12 14 | V2.0.0 on 2025-1-20,refactor by C++ 15 | V3.0.0 on 2025-4-8,redesign refer to SimpleFOC 16 | V3.0.1 on 2025-5-4,optimize enable() and disable() process 17 | * */ 18 | 19 | #ifndef BLED_Driver_DRV8300_H 20 | #define BLED_Driver_DRV8300_H 21 | 22 | #include 23 | #include "tim.h" 24 | #include "BLDC_Driver.h" 25 | 26 | class BLDC_Driver_DRV8300 final : public BLDC_Driver { 27 | public: 28 | ~BLDC_Driver_DRV8300() override = default; 29 | 30 | BLDC_Driver_DRV8300(TIM_HandleTypeDef *htim, const uint16_t MaxDuty) : 31 | htim(htim), MaxDuty(MaxDuty) { initialized = true; } 32 | 33 | void init() override { initialized = true; } 34 | 35 | void enable() override { 36 | //打开所有PWM通道输出 37 | HAL_TIM_PWM_Start(htim, TIM_CHANNEL_1); 38 | HAL_TIM_PWM_Start(htim, TIM_CHANNEL_2); 39 | HAL_TIM_PWM_Start(htim, TIM_CHANNEL_3); 40 | HAL_TIMEx_PWMN_Start(htim, TIM_CHANNEL_1); 41 | HAL_TIMEx_PWMN_Start(htim, TIM_CHANNEL_2); 42 | HAL_TIMEx_PWMN_Start(htim, TIM_CHANNEL_3); 43 | enabled = true; 44 | } 45 | 46 | void disable() override { 47 | // 设置占空比为0 48 | set_duty(0, 0, 0); 49 | // 关闭所有PWM通道输出 50 | HAL_TIM_PWM_Stop(htim, TIM_CHANNEL_1); 51 | HAL_TIM_PWM_Stop(htim, TIM_CHANNEL_2); 52 | HAL_TIM_PWM_Stop(htim, TIM_CHANNEL_3); 53 | HAL_TIMEx_PWMN_Stop(htim, TIM_CHANNEL_1); 54 | HAL_TIMEx_PWMN_Stop(htim, TIM_CHANNEL_2); 55 | HAL_TIMEx_PWMN_Stop(htim, TIM_CHANNEL_3); 56 | enabled = false; 57 | } 58 | 59 | void set_duty(float u, float v, float w) override { 60 | if (enabled) { 61 | u *= static_cast(MaxDuty); 62 | v *= static_cast(MaxDuty); 63 | w *= static_cast(MaxDuty); 64 | //设置PWM占空比 65 | __HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_1, u); 66 | __HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_3, v); 67 | __HAL_TIM_SET_COMPARE(htim, TIM_CHANNEL_2, w); 68 | } 69 | } 70 | 71 | private: 72 | TIM_HandleTypeDef *htim; 73 | uint16_t MaxDuty; 74 | }; 75 | 76 | #endif //BLED_Driver_DRV8300_H 77 | -------------------------------------------------------------------------------- /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) 2024 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_GPIOF_CLK_ENABLE(); 49 | __HAL_RCC_GPIOA_CLK_ENABLE(); 50 | __HAL_RCC_GPIOC_CLK_ENABLE(); 51 | __HAL_RCC_GPIOB_CLK_ENABLE(); 52 | 53 | /*Configure GPIO pin Output Level */ 54 | HAL_GPIO_WritePin(GPIOF, LED_G_Pin|LED_R_Pin, GPIO_PIN_SET); 55 | 56 | /*Configure GPIO pin Output Level */ 57 | HAL_GPIO_WritePin(SPI1_CSn_GPIO_Port, SPI1_CSn_Pin, GPIO_PIN_RESET); 58 | 59 | /*Configure GPIO pins : LED_G_Pin LED_R_Pin */ 60 | GPIO_InitStruct.Pin = LED_G_Pin|LED_R_Pin; 61 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 62 | GPIO_InitStruct.Pull = GPIO_NOPULL; 63 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 64 | HAL_GPIO_Init(GPIOF, &GPIO_InitStruct); 65 | 66 | /*Configure GPIO pin : SPI1_CSn_Pin */ 67 | GPIO_InitStruct.Pin = SPI1_CSn_Pin; 68 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 69 | GPIO_InitStruct.Pull = GPIO_NOPULL; 70 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 71 | HAL_GPIO_Init(SPI1_CSn_GPIO_Port, &GPIO_InitStruct); 72 | 73 | } 74 | 75 | /* USER CODE BEGIN 2 */ 76 | 77 | /* USER CODE END 2 */ 78 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/freertos_mpool.h: -------------------------------------------------------------------------------- 1 | /* -------------------------------------------------------------------------- 2 | * Copyright (c) 2013-2020 Arm Limited. All rights reserved. 3 | * 4 | * SPDX-License-Identifier: Apache-2.0 5 | * 6 | * Licensed under the Apache License, Version 2.0 (the License); you may 7 | * not use this file except in compliance with the License. 8 | * You may obtain a copy of the License at 9 | * 10 | * www.apache.org/licenses/LICENSE-2.0 11 | * 12 | * Unless required by applicable law or agreed to in writing, software 13 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 14 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 15 | * See the License for the specific language governing permissions and 16 | * limitations under the License. 17 | * 18 | * Name: freertos_mpool.h 19 | * Purpose: CMSIS RTOS2 wrapper for FreeRTOS 20 | * 21 | *---------------------------------------------------------------------------*/ 22 | 23 | #ifndef FREERTOS_MPOOL_H_ 24 | #define FREERTOS_MPOOL_H_ 25 | 26 | #include 27 | #include "FreeRTOS.h" 28 | #include "semphr.h" 29 | 30 | /* Memory Pool implementation definitions */ 31 | #define MPOOL_STATUS 0x5EED0000U 32 | 33 | /* Memory Block header */ 34 | typedef struct { 35 | void *next; /* Pointer to next block */ 36 | } MemPoolBlock_t; 37 | 38 | /* Memory Pool control block */ 39 | typedef struct MemPoolDef_t { 40 | MemPoolBlock_t *head; /* Pointer to head block */ 41 | SemaphoreHandle_t sem; /* Pool semaphore handle */ 42 | uint8_t *mem_arr; /* Pool memory array */ 43 | uint32_t mem_sz; /* Pool memory array size */ 44 | const char *name; /* Pointer to name string */ 45 | uint32_t bl_sz; /* Size of a single block */ 46 | uint32_t bl_cnt; /* Number of blocks */ 47 | uint32_t n; /* Block allocation index */ 48 | volatile uint32_t status; /* Object status flags */ 49 | #if (configSUPPORT_STATIC_ALLOCATION == 1) 50 | StaticSemaphore_t mem_sem; /* Semaphore object memory */ 51 | #endif 52 | } MemPool_t; 53 | 54 | /* No need to hide static object type, just align to coding style */ 55 | #define StaticMemPool_t MemPool_t 56 | 57 | /* Define memory pool control block size */ 58 | #define MEMPOOL_CB_SIZE (sizeof(StaticMemPool_t)) 59 | 60 | /* Define size of the byte array required to create count of blocks of given size */ 61 | #define MEMPOOL_ARR_SIZE(bl_count, bl_size) (((((bl_size) + (4 - 1)) / 4) * 4)*(bl_count)) 62 | 63 | #endif /* FREERTOS_MPOOL_H_ */ 64 | -------------------------------------------------------------------------------- /Core/Src/stm32g4xx_hal_msp.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file stm32g4xx_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) 2024 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 | 66 | /* USER CODE BEGIN MspInit 0 */ 67 | 68 | /* USER CODE END MspInit 0 */ 69 | 70 | __HAL_RCC_SYSCFG_CLK_ENABLE(); 71 | __HAL_RCC_PWR_CLK_ENABLE(); 72 | 73 | /* System interrupt init*/ 74 | /* PendSV_IRQn interrupt configuration */ 75 | HAL_NVIC_SetPriority(PendSV_IRQn, 15, 0); 76 | 77 | /** Disable the internal Pull-Up in Dead Battery pins of UCPD peripheral 78 | */ 79 | HAL_PWREx_DisableUCPDDeadBattery(); 80 | 81 | /* USER CODE BEGIN MspInit 1 */ 82 | 83 | /* USER CODE END MspInit 1 */ 84 | } 85 | 86 | /* USER CODE BEGIN 1 */ 87 | 88 | /* USER CODE END 1 */ 89 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_req.h 4 | * @author MCD Application Team 5 | * @brief Header file for the usbd_req.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USB_REQUEST_H 22 | #define __USB_REQUEST_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_def.h" 30 | 31 | 32 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 33 | * @{ 34 | */ 35 | 36 | /** @defgroup USBD_REQ 37 | * @brief header file for the usbd_req.c file 38 | * @{ 39 | */ 40 | 41 | /** @defgroup USBD_REQ_Exported_Defines 42 | * @{ 43 | */ 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @defgroup USBD_REQ_Exported_Types 50 | * @{ 51 | */ 52 | /** 53 | * @} 54 | */ 55 | 56 | 57 | 58 | /** @defgroup USBD_REQ_Exported_Macros 59 | * @{ 60 | */ 61 | /** 62 | * @} 63 | */ 64 | 65 | /** @defgroup USBD_REQ_Exported_Variables 66 | * @{ 67 | */ 68 | /** 69 | * @} 70 | */ 71 | 72 | /** @defgroup USBD_REQ_Exported_FunctionsPrototype 73 | * @{ 74 | */ 75 | 76 | USBD_StatusTypeDef USBD_StdDevReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 77 | USBD_StatusTypeDef USBD_StdItfReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 78 | USBD_StatusTypeDef USBD_StdEPReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 79 | 80 | void USBD_CtlError(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 81 | void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata); 82 | void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len); 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | #ifdef __cplusplus 89 | } 90 | #endif 91 | 92 | #endif /* __USB_REQUEST_H */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | 103 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 104 | -------------------------------------------------------------------------------- /USB_Device/App/usb_device.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usb_device.h 5 | * @version : v3.0_Cube 6 | * @brief : Header for usb_device.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2025 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 __USB_DEVICE__H__ 23 | #define __USB_DEVICE__H__ 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include "stm32g4xx.h" 31 | #include "stm32g4xx_hal.h" 32 | #include "usbd_def.h" 33 | 34 | /* USER CODE BEGIN INCLUDE */ 35 | 36 | /* USER CODE END INCLUDE */ 37 | 38 | /** @addtogroup USBD_OTG_DRIVER 39 | * @{ 40 | */ 41 | 42 | /** @defgroup USBD_DEVICE USBD_DEVICE 43 | * @brief Device file for Usb otg low level driver. 44 | * @{ 45 | */ 46 | 47 | /** @defgroup USBD_DEVICE_Exported_Variables USBD_DEVICE_Exported_Variables 48 | * @brief Public variables. 49 | * @{ 50 | */ 51 | 52 | /* Private variables ---------------------------------------------------------*/ 53 | /* USER CODE BEGIN PV */ 54 | 55 | /* USER CODE END PV */ 56 | 57 | /* Private function prototypes -----------------------------------------------*/ 58 | /* USER CODE BEGIN PFP */ 59 | 60 | /* USER CODE END PFP */ 61 | 62 | /* 63 | * -- Insert your variables declaration here -- 64 | */ 65 | /* USER CODE BEGIN VARIABLES */ 66 | 67 | /* USER CODE END VARIABLES */ 68 | /** 69 | * @} 70 | */ 71 | 72 | /** @defgroup USBD_DEVICE_Exported_FunctionsPrototype USBD_DEVICE_Exported_FunctionsPrototype 73 | * @brief Declaration of public functions for Usb device. 74 | * @{ 75 | */ 76 | 77 | /** USB Device initialization function. */ 78 | void MX_USB_Device_Init(void); 79 | 80 | /* 81 | * -- Insert functions declaration here -- 82 | */ 83 | /* USER CODE BEGIN FD */ 84 | 85 | /* USER CODE END FD */ 86 | /** 87 | * @} 88 | */ 89 | 90 | /** 91 | * @} 92 | */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | #ifdef __cplusplus 99 | } 100 | #endif 101 | 102 | #endif /* __USB_DEVICE__H__ */ 103 | 104 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_pcd_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32g4xx_hal_pcd_ex.h 4 | * @author MCD Application Team 5 | * @brief Header file of PCD HAL Extension module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2019 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 | 19 | /* Define to prevent recursive inclusion -------------------------------------*/ 20 | #ifndef STM32G4xx_HAL_PCD_EX_H 21 | #define STM32G4xx_HAL_PCD_EX_H 22 | 23 | #ifdef __cplusplus 24 | extern "C" { 25 | #endif /* __cplusplus */ 26 | 27 | /* Includes ------------------------------------------------------------------*/ 28 | #include "stm32g4xx_hal_def.h" 29 | 30 | #if defined (USB) 31 | /** @addtogroup STM32G4xx_HAL_Driver 32 | * @{ 33 | */ 34 | 35 | /** @addtogroup PCDEx 36 | * @{ 37 | */ 38 | /* Exported types ------------------------------------------------------------*/ 39 | /* Exported constants --------------------------------------------------------*/ 40 | /* Exported macros -----------------------------------------------------------*/ 41 | /* Exported functions --------------------------------------------------------*/ 42 | /** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions 43 | * @{ 44 | */ 45 | /** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions 46 | * @{ 47 | */ 48 | 49 | 50 | HAL_StatusTypeDef HAL_PCDEx_PMAConfig(PCD_HandleTypeDef *hpcd, uint16_t ep_addr, 51 | uint16_t ep_kind, uint32_t pmaadress); 52 | 53 | 54 | HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); 55 | HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); 56 | 57 | 58 | HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); 59 | HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); 60 | void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); 61 | 62 | void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); 63 | void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); 64 | 65 | /** 66 | * @} 67 | */ 68 | 69 | /** 70 | * @} 71 | */ 72 | 73 | /** 74 | * @} 75 | */ 76 | 77 | /** 78 | * @} 79 | */ 80 | #endif /* defined (USB) */ 81 | 82 | #ifdef __cplusplus 83 | } 84 | #endif /* __cplusplus */ 85 | 86 | 87 | #endif /* STM32G4xx_HAL_PCD_EX_H */ 88 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/Inc/stm32g4xx_hal_flash_ex.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32g4xx_hal_flash_ex.h 4 | * @author MCD Application Team 5 | * @brief Header file of FLASH HAL Extended module. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2019 STMicroelectronics. 10 | * All rights reserved. 11 | * 12 | * This software is licensed under terms that can be found in the LICENSE file in 13 | * 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 | /* Define to prevent recursive inclusion -------------------------------------*/ 19 | #ifndef STM32G4xx_HAL_FLASH_EX_H 20 | #define STM32G4xx_HAL_FLASH_EX_H 21 | 22 | #ifdef __cplusplus 23 | extern "C" { 24 | #endif 25 | 26 | /* Includes ------------------------------------------------------------------*/ 27 | #include "stm32g4xx_hal_def.h" 28 | 29 | /** @addtogroup STM32G4xx_HAL_Driver 30 | * @{ 31 | */ 32 | 33 | /** @addtogroup FLASHEx 34 | * @{ 35 | */ 36 | 37 | /* Exported types ------------------------------------------------------------*/ 38 | 39 | /* Exported constants --------------------------------------------------------*/ 40 | 41 | /* Exported macro ------------------------------------------------------------*/ 42 | 43 | /* Exported functions --------------------------------------------------------*/ 44 | /** @addtogroup FLASHEx_Exported_Functions 45 | * @{ 46 | */ 47 | 48 | /* Extended Program operation functions *************************************/ 49 | /** @addtogroup FLASHEx_Exported_Functions_Group1 50 | * @{ 51 | */ 52 | HAL_StatusTypeDef HAL_FLASHEx_Erase(FLASH_EraseInitTypeDef *pEraseInit, uint32_t *PageError); 53 | HAL_StatusTypeDef HAL_FLASHEx_Erase_IT(FLASH_EraseInitTypeDef *pEraseInit); 54 | HAL_StatusTypeDef HAL_FLASHEx_OBProgram(FLASH_OBProgramInitTypeDef *pOBInit); 55 | void HAL_FLASHEx_OBGetConfig(FLASH_OBProgramInitTypeDef *pOBInit); 56 | HAL_StatusTypeDef HAL_FLASHEx_EnableSecMemProtection(uint32_t Bank); 57 | void HAL_FLASHEx_EnableDebugger(void); 58 | void HAL_FLASHEx_DisableDebugger(void); 59 | /** 60 | * @} 61 | */ 62 | 63 | /** 64 | * @} 65 | */ 66 | 67 | /** @addtogroup FLASHEx_Private_Functions 68 | * @{ 69 | */ 70 | void FLASH_PageErase(uint32_t Page, uint32_t Banks); 71 | void FLASH_FlushCaches(void); 72 | /** 73 | * @} 74 | */ 75 | 76 | /** 77 | * @} 78 | */ 79 | 80 | /** 81 | * @} 82 | */ 83 | 84 | #ifdef __cplusplus 85 | } 86 | #endif 87 | 88 | #endif /* STM32G4xx_HAL_FLASH_EX_H */ 89 | 90 | -------------------------------------------------------------------------------- /Drivers/CMSIS/Device/ST/STM32G4xx/Include/system_stm32g4xx.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file system_stm32g4xx.h 4 | * @author MCD Application Team 5 | * @brief CMSIS Cortex-M4 Device System Source File for STM32G4xx devices. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2019 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 | 19 | /** @addtogroup CMSIS 20 | * @{ 21 | */ 22 | 23 | /** @addtogroup stm32g4xx_system 24 | * @{ 25 | */ 26 | 27 | /** 28 | * @brief Define to prevent recursive inclusion 29 | */ 30 | #ifndef __SYSTEM_STM32G4XX_H 31 | #define __SYSTEM_STM32G4XX_H 32 | 33 | #ifdef __cplusplus 34 | extern "C" { 35 | #endif 36 | 37 | /** @addtogroup STM32G4xx_System_Includes 38 | * @{ 39 | */ 40 | 41 | /** 42 | * @} 43 | */ 44 | 45 | 46 | /** @addtogroup STM32G4xx_System_Exported_Variables 47 | * @{ 48 | */ 49 | /* The SystemCoreClock variable is updated in three ways: 50 | 1) by calling CMSIS function SystemCoreClockUpdate() 51 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq() 52 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency 53 | Note: If you use this function to configure the system clock; then there 54 | is no need to call the 2 first functions listed above, since SystemCoreClock 55 | variable is updated automatically. 56 | */ 57 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ 58 | 59 | extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ 60 | extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ 61 | 62 | /** 63 | * @} 64 | */ 65 | 66 | /** @addtogroup STM32G4xx_System_Exported_Constants 67 | * @{ 68 | */ 69 | 70 | /** 71 | * @} 72 | */ 73 | 74 | /** @addtogroup STM32G4xx_System_Exported_Macros 75 | * @{ 76 | */ 77 | 78 | /** 79 | * @} 80 | */ 81 | 82 | /** @addtogroup STM32G4xx_System_Exported_Functions 83 | * @{ 84 | */ 85 | 86 | extern void SystemInit(void); 87 | extern void SystemCoreClockUpdate(void); 88 | /** 89 | * @} 90 | */ 91 | 92 | #ifdef __cplusplus 93 | } 94 | #endif 95 | 96 | #endif /*__SYSTEM_STM32G4XX_H */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /** 103 | * @} 104 | */ 105 | -------------------------------------------------------------------------------- /USB_Device/App/usb_device.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usb_device.c 5 | * @version : v3.0_Cube 6 | * @brief : This file implements the USB Device 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2025 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 | 23 | #include "usb_device.h" 24 | #include "usbd_core.h" 25 | #include "usbd_desc.h" 26 | #include "usbd_cdc.h" 27 | #include "usbd_cdc_if.h" 28 | 29 | /* USER CODE BEGIN Includes */ 30 | 31 | /* USER CODE END Includes */ 32 | 33 | /* USER CODE BEGIN PV */ 34 | /* Private variables ---------------------------------------------------------*/ 35 | 36 | /* USER CODE END PV */ 37 | 38 | /* USER CODE BEGIN PFP */ 39 | /* Private function prototypes -----------------------------------------------*/ 40 | 41 | /* USER CODE END PFP */ 42 | 43 | extern void Error_Handler(void); 44 | /* USB Device Core handle declaration. */ 45 | USBD_HandleTypeDef hUsbDeviceFS; 46 | extern USBD_DescriptorsTypeDef CDC_Desc; 47 | 48 | /* 49 | * -- Insert your variables declaration here -- 50 | */ 51 | /* USER CODE BEGIN 0 */ 52 | 53 | /* USER CODE END 0 */ 54 | 55 | /* 56 | * -- Insert your external function declaration here -- 57 | */ 58 | /* USER CODE BEGIN 1 */ 59 | 60 | /* USER CODE END 1 */ 61 | 62 | /** 63 | * Init USB device Library, add supported class and start the library 64 | * @retval None 65 | */ 66 | void MX_USB_Device_Init(void) 67 | { 68 | /* USER CODE BEGIN USB_Device_Init_PreTreatment */ 69 | 70 | /* USER CODE END USB_Device_Init_PreTreatment */ 71 | 72 | /* Init Device Library, add supported class and start the library. */ 73 | if (USBD_Init(&hUsbDeviceFS, &CDC_Desc, DEVICE_FS) != USBD_OK) { 74 | Error_Handler(); 75 | } 76 | if (USBD_RegisterClass(&hUsbDeviceFS, &USBD_CDC) != USBD_OK) { 77 | Error_Handler(); 78 | } 79 | if (USBD_CDC_RegisterInterface(&hUsbDeviceFS, &USBD_Interface_fops_FS) != USBD_OK) { 80 | Error_Handler(); 81 | } 82 | if (USBD_Start(&hUsbDeviceFS) != USBD_OK) { 83 | Error_Handler(); 84 | } 85 | /* USER CODE BEGIN USB_Device_Init_PostTreatment */ 86 | 87 | /* USER CODE END USB_Device_Init_PostTreatment */ 88 | } 89 | 90 | /** 91 | * @} 92 | */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | -------------------------------------------------------------------------------- /BSP/sys_public.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @name sys_public.h 3 | * @brief 用于支持简单平台移植的中间层 4 | * @detail 5 | * @author Haoqi Liu 6 | * @date 25-4-17 7 | * @version V3.0.0 8 | * @note 用户需要根据提示定义相关宏函数,其中,MAX_DELAY应与delay()匹配 9 | * @warning 10 | * @par 历史版本 11 | V1.0.0创建于24-11-24 12 | V2.0.0创建于24-11-27,修改打印日志宏函数命名,添加更多日志打印方式 13 | V3.0.0创建于25-4-17,重写new和delete函数 14 | V3.1.0创建于25-9-11,添加另外两个重载delete函数 15 | * */ 16 | 17 | #ifndef SYS_PUBLIC_H 18 | #define SYS_PUBLIC_H 19 | 20 | #ifdef __cplusplus 21 | extern "C" { 22 | #endif 23 | 24 | /**====================================User Code Begin====================================**/ 25 | #include "cmsis_os2.h" 26 | /**=====================================User Code End=====================================**/ 27 | 28 | /**====================================用户需要定义的部分====================================**/ 29 | #define SYS_LOG_ENABLE 0 //开启系统日志,注意:关闭后也可在代码里使用log(),只是没有动作 30 | #define MAX_DELAY portMAX_DELAY //最大延时时间,单位ms 31 | #define TX_BUFFER_LENGTH 64 //系统日志输出缓冲区大小 32 | 33 | #define delay(ms) osDelay(ms) //延时函数 34 | #define get_tick() xTaskGetTickCount() //获取系统滴答计数 35 | #define sys_log_function(...) printf(__VA_ARGS__) 36 | /**=======================================================================================**/ 37 | 38 | #ifdef DEBUG 39 | #endif 40 | 41 | #if SYS_LOG_ENABLE == 1 42 | #define sys_log(...) sys_log_function(__VA_ARGS__) 43 | #define sys_log_info(...) sys_log_function("INFO: " __VA_ARGS__) 44 | #define sys_log_warning(...) sys_log_function("WARNING: " __VA_ARGS__) 45 | #define sys_log_error(...) sys_log_function("ERROR: " __VA_ARGS__) 46 | #else 47 | #define sys_log(...) ((void)0U) 48 | #define sys_log_info(...) ((void)0U) 49 | #define sys_log_warning(...) ((void)0U) 50 | #define sys_log_error(...) ((void)0U) 51 | #endif 52 | 53 | #ifdef __cplusplus 54 | }; 55 | 56 | /**====================================User Code Begin====================================**/ 57 | #include 58 | #include "FreeRTOS.h" 59 | /**=====================================User Code End=====================================**/ 60 | inline void* operator new(const std::size_t size) { 61 | return pvPortMalloc(size); 62 | } 63 | 64 | inline void* operator new[](const std::size_t size) { 65 | return pvPortMalloc(size); 66 | } 67 | 68 | inline void operator delete(void *ptr) { 69 | vPortFree(ptr); 70 | } 71 | 72 | inline void operator delete(void *ptr, std::size_t) { 73 | vPortFree(ptr); 74 | } 75 | 76 | inline void operator delete[](void *ptr) { 77 | vPortFree(ptr); 78 | } 79 | 80 | inline void operator delete[](void *ptr, std::size_t) { 81 | vPortFree(ptr); 82 | } 83 | #endif 84 | 85 | #endif //SYS_PUBLIC_H 86 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.22) 2 | 3 | # 4 | # This file is generated only once, 5 | # and is not re-generated if converter is called multiple times. 6 | # 7 | # User is free to modify the file as much as necessary 8 | # 9 | 10 | # Setup compiler settings 11 | set(CMAKE_C_STANDARD 11) 12 | set(CMAKE_CXX_STANDARD 20) 13 | set(CMAKE_C_STANDARD_REQUIRED ON) 14 | set(CMAKE_C_EXTENSIONS ON) 15 | 16 | 17 | # Define the build type 18 | if (NOT CMAKE_BUILD_TYPE) 19 | set(CMAKE_BUILD_TYPE "Debug") 20 | endif () 21 | 22 | # Set the project name 23 | set(CMAKE_PROJECT_NAME FOC_QD4310) 24 | 25 | # Include toolchain file 26 | include("cmake/gcc-arm-none-eabi.cmake") 27 | 28 | # Enable compile command to ease indexing with e.g. clangd 29 | set(CMAKE_EXPORT_COMPILE_COMMANDS TRUE) 30 | 31 | # Enable CMake support for ASM and C languages 32 | enable_language(C ASM) 33 | 34 | # Core project settings 35 | project(${CMAKE_PROJECT_NAME}) 36 | message("Build type: " ${CMAKE_BUILD_TYPE}) 37 | 38 | # Create an executable object type 39 | add_executable(${CMAKE_PROJECT_NAME}) 40 | 41 | # Add STM32CubeMX generated sources 42 | add_subdirectory(cmake/stm32cubemx) 43 | 44 | add_subdirectory(UserLib/FOC) 45 | add_subdirectory(UserLib/PID) 46 | add_subdirectory(UserLib/LetterShell) 47 | 48 | # Link directories setup 49 | target_link_directories(${CMAKE_PROJECT_NAME} PRIVATE 50 | # Add user defined library search paths 51 | ) 52 | 53 | file(GLOB_RECURSE APPLICATION_SOURCES "./Applications/*.c" "./Applications/*.cpp") 54 | file(GLOB_RECURSE BSP_SOURCES "./BSP/*.c" "./BSP/*.cpp") 55 | 56 | # Add sources to executable 57 | target_sources(${CMAKE_PROJECT_NAME} PRIVATE 58 | # Add user sources here 59 | ${APPLICATION_SOURCES} 60 | ${BSP_SOURCES} 61 | ) 62 | 63 | # Add include paths 64 | target_include_directories(${CMAKE_PROJECT_NAME} PRIVATE 65 | # Add user defined include paths 66 | Applications/Inc/ 67 | BSP/ 68 | ) 69 | 70 | # Add project symbols (macros) 71 | target_compile_definitions(${CMAKE_PROJECT_NAME} PRIVATE 72 | # Add user defined symbols 73 | ) 74 | 75 | # Add linked libraries 76 | target_link_libraries(${CMAKE_PROJECT_NAME} 77 | stm32cubemx 78 | 79 | # Add user defined libraries 80 | foc 81 | pid 82 | letter_shell 83 | ) 84 | 85 | # 查找 UserLib 下的所有源文件 86 | file(GLOB_RECURSE USERLIB_SOURCES "UserLib/*.*" "Applications/*.*" "BSP/*.*") 87 | 88 | # 为每个 UserLib 源文件添加编译选项 -include public.h 89 | foreach (SRC ${USERLIB_SOURCES}) 90 | set_source_files_properties(${SRC} PROPERTIES COMPILE_OPTIONS "-include;sys_public.h") 91 | endforeach () 92 | 93 | add_custom_command(TARGET ${CMAKE_PROJECT_NAME} POST_BUILD 94 | COMMAND ${CMAKE_OBJCOPY} -O binary $ ${CMAKE_PROJECT_NAME}.bin 95 | COMMAND ${CMAKE_OBJCOPY} -O ihex $ ${CMAKE_PROJECT_NAME}.hex 96 | ) -------------------------------------------------------------------------------- /Applications/Src/FOCTask.cpp: -------------------------------------------------------------------------------- 1 | #include "task_public.h" 2 | #include "FOC.h" 3 | #include "FOC_config.h" 4 | #include "tim.h" 5 | #include "spi.h" 6 | #include "adc.h" 7 | #include "cmsis_os2.h" 8 | #include "Encoder_MT6825.h" 9 | #include "BLDC_Driver_FD6288.h" 10 | #include "Storage_EmbeddedFlash.h" 11 | #include "CurrentSensor_Embed.h" 12 | #include "filters.h" 13 | 14 | BLDC_Driver_DRV8300 bldc_driver(&htim1, 2125); 15 | Encoder_MT6825 bldc_encoder(SPI1_CSn_GPIO_Port, SPI1_CSn_Pin, &hspi1); 16 | CurrentSensor_Embed current_sensor(&hadc1, &hadc2); 17 | 18 | LowPassFilter_2_Order CurrentQFilter(0.00005f, 1500); // 20kHz 19 | LowPassFilter_2_Order CurrentDFilter(0.00005f, 1500); // 20kHz 20 | LowPassFilter_2_Order SpeedFilter(0.00005f, 300); // 20kHz 21 | 22 | __attribute__((section(".ccmram"))) 23 | FOC foc(FOC_POLE_PAIRS, 1000, 20000, 24 | CurrentQFilter, CurrentDFilter, SpeedFilter, 25 | bldc_driver, bldc_encoder, storage, current_sensor, 26 | PID(PID::delta_type, 27 | FOC_CURRENT_KP, 28 | FOC_CURRENT_KI, 29 | FOC_CURRENT_KD, 30 | NAN, 31 | NAN, 32 | 1.0f, 33 | -1.0f 34 | ), 35 | PID(PID::delta_type, 36 | FOC_CURRENT_KP, 37 | FOC_CURRENT_KI, 38 | FOC_CURRENT_KD, 39 | NAN, 40 | NAN, 41 | 1.0f, 42 | -1.0f 43 | ), 44 | PID(PID::position_type, 45 | FOC_SPEED_KP, 46 | FOC_SPEED_KI, 47 | FOC_SPEED_KD, 48 | 2e3f, 49 | -2e3f, 50 | FOC_MAX_CURRENT, 51 | -FOC_MAX_CURRENT 52 | ), 53 | PID(PID::position_type, 54 | FOC_ANGLE_KP, 55 | FOC_ANGLE_KI, 56 | FOC_ANGLE_KD, 57 | NAN, 58 | NAN, 59 | FOC_MAX_SPEED, 60 | -FOC_MAX_SPEED 61 | ) 62 | ); 63 | 64 | void StartFOCTask(void *argument) { 65 | HAL_TIM_Base_Start_IT(&htim6); // 开启速度环位置环中断控制 66 | HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_4); //开启PWM输出,用于触发ADC采样 67 | foc.init(); // 初始化FOC 68 | while (true) { 69 | if (!LL_ADC_REG_IsConversionOngoing(hadc1.Instance)) { 70 | LL_ADC_REG_StartConversion(hadc1.Instance); 71 | foc.updateVoltage(hadc1.Instance->DR / 4095.0f * 3.3f / 2 * 17); 72 | LL_ADC_REG_StopConversion(hadc1.Instance); 73 | } 74 | delay(1); 75 | } 76 | } 77 | 78 | __attribute__((section(".ccmram_func"))) 79 | void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef *hadc) { 80 | if (&hadc1 == hadc) { 81 | current_sensor.update(); 82 | foc.loopCtrl(); 83 | } 84 | } 85 | 86 | __attribute__((section(".ccmram_func"))) 87 | void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) { 88 | if (&htim6 == htim) { 89 | foc.Ctrl_ISR(); 90 | } 91 | } 92 | -------------------------------------------------------------------------------- /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) 2023 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 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_ioreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_ioreq.h 4 | * @author MCD Application Team 5 | * @brief Header file for the usbd_ioreq.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USBD_IOREQ_H 22 | #define __USBD_IOREQ_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_def.h" 30 | #include "usbd_core.h" 31 | 32 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 33 | * @{ 34 | */ 35 | 36 | /** @defgroup USBD_IOREQ 37 | * @brief header file for the usbd_ioreq.c file 38 | * @{ 39 | */ 40 | 41 | /** @defgroup USBD_IOREQ_Exported_Defines 42 | * @{ 43 | */ 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @defgroup USBD_IOREQ_Exported_Types 50 | * @{ 51 | */ 52 | 53 | 54 | /** 55 | * @} 56 | */ 57 | 58 | 59 | 60 | /** @defgroup USBD_IOREQ_Exported_Macros 61 | * @{ 62 | */ 63 | 64 | /** 65 | * @} 66 | */ 67 | 68 | /** @defgroup USBD_IOREQ_Exported_Variables 69 | * @{ 70 | */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_IOREQ_Exported_FunctionsPrototype 77 | * @{ 78 | */ 79 | 80 | USBD_StatusTypeDef USBD_CtlSendData(USBD_HandleTypeDef *pdev, 81 | uint8_t *pbuf, uint32_t len); 82 | 83 | USBD_StatusTypeDef USBD_CtlContinueSendData(USBD_HandleTypeDef *pdev, 84 | uint8_t *pbuf, uint32_t len); 85 | 86 | USBD_StatusTypeDef USBD_CtlPrepareRx(USBD_HandleTypeDef *pdev, 87 | uint8_t *pbuf, uint32_t len); 88 | 89 | USBD_StatusTypeDef USBD_CtlContinueRx(USBD_HandleTypeDef *pdev, 90 | uint8_t *pbuf, uint32_t len); 91 | 92 | USBD_StatusTypeDef USBD_CtlSendStatus(USBD_HandleTypeDef *pdev); 93 | USBD_StatusTypeDef USBD_CtlReceiveStatus(USBD_HandleTypeDef *pdev); 94 | 95 | uint32_t USBD_GetRxCount(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 96 | 97 | /** 98 | * @} 99 | */ 100 | 101 | #ifdef __cplusplus 102 | } 103 | #endif 104 | 105 | #endif /* __USBD_IOREQ_H */ 106 | 107 | /** 108 | * @} 109 | */ 110 | 111 | /** 112 | * @} 113 | */ 114 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 115 | -------------------------------------------------------------------------------- /BSP/retarget/retarget.cpp: -------------------------------------------------------------------------------- 1 | #include <_ansi.h> 2 | #include <_syslist.h> 3 | #include 4 | #include 5 | #include 6 | #include "retarget.h" 7 | #include 8 | 9 | #include "usbd_cdc_if.h" 10 | #include "CharCircularQueue.h" 11 | #include "CDC_Tx_DualBuffer.h" 12 | 13 | #if !defined(OS_USE_SEMIHOSTING) 14 | 15 | #define STDIN_FILENO 0 16 | #define STDOUT_FILENO 1 17 | #define STDERR_FILENO 2 18 | 19 | void RetargetInit() { 20 | #if USE_TinyPrintf == 0 && STDIO_SUPPORT == 1 21 | /* Disable I/O buffering for STDOUT stream, so that 22 | * chars are sent out as soon as they are printed. */ 23 | setvbuf(stdout, NULL, _IONBF, 0); 24 | #endif 25 | } 26 | 27 | CharCircularQueue rx_queue{128}; 28 | TxDualBuffer tx_buffer(&CDC_Transmit_FS); 29 | 30 | void CDC_Receive_FS_Callback(uint8_t *Buf, uint32_t *Len) { 31 | auto length = *Len; 32 | while (length--) rx_queue.enqueue(*(Buf++)); 33 | } 34 | 35 | void CDC_TransmitCplt_FS_Callback() { 36 | tx_buffer.transmitComplete(); 37 | } 38 | 39 | signed short shellRead(char *data, unsigned short len) { 40 | signed short i = 0; 41 | for (i = 0; i < len && !rx_queue.isEmpty(); ++i, ++data) { 42 | rx_queue.dequeue(*data); 43 | } 44 | delay(1); // 延时1ms,因为shellTask是死循环一点delay都没有,为了让IDLE线程能够运行以释放内存等 45 | return i; 46 | } 47 | 48 | signed short shellWrite(char *data, unsigned short len) { 49 | return tx_buffer.inBuffer(data, len) ? 0 : -1; 50 | } 51 | 52 | #if USE_TinyPrintf == 1 53 | // provide your own _putchar() low level function as console/serial output 54 | void _putchar(char character) { 55 | shellWrite(&character, 1); 56 | } 57 | #endif 58 | 59 | #if STDIO_SUPPORT == 1 60 | int _write(int fd, char *ptr, int len) { 61 | if (fd == STDOUT_FILENO || fd == STDERR_FILENO) { 62 | shellWrite(ptr, len); 63 | if (shellWrite(ptr, len) == 0) 64 | return len; 65 | else 66 | return EIO; 67 | } 68 | errno = EBADF; 69 | return -1; 70 | } 71 | 72 | int _read(int fd, char *ptr, int len) { 73 | if (fd == STDIN_FILENO) { 74 | shellRead(ptr, 1); 75 | if (shellRead(ptr, 1) == 0) 76 | return 1; 77 | else 78 | return EIO; 79 | } 80 | errno = EBADF; 81 | return -1; 82 | } 83 | 84 | int _close(int fd) { 85 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) 86 | return 0; 87 | 88 | errno = EBADF; 89 | return -1; 90 | } 91 | 92 | int _fstat(int fd, struct stat *st) { 93 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) { 94 | st->st_mode = S_IFCHR; 95 | return 0; 96 | } 97 | 98 | errno = EBADF; 99 | return 0; 100 | } 101 | 102 | int _isatty(int fd) { 103 | if (fd >= STDIN_FILENO && fd <= STDERR_FILENO) 104 | return 1; 105 | 106 | errno = EBADF; 107 | return 0; 108 | } 109 | 110 | int _lseek(int fd, int ptr, int dir) { 111 | (void)fd; 112 | (void)ptr; 113 | (void)dir; 114 | 115 | errno = EBADF; 116 | return -1; 117 | } 118 | #endif 119 | 120 | #endif //#if !defined(OS_USE_SEMIHOSTING) 121 | -------------------------------------------------------------------------------- /BSP/Storage_EmbeddedFlash.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by 26757 on 25-4-30. 3 | // 4 | 5 | #include "Storage_EmbeddedFlash.h" 6 | #include "main.h" 7 | 8 | #define STORAGE_ADDRESS_BASE 0x0801D800 9 | 10 | //FLASH中存放数据的区域,也用于烧录时擦除这些数据,注意:只读! 11 | // __attribute__((section(".flash_data"))) uint8_t storage_buffer_to_erase[FLASH_PAGE_SIZE * 5]; 12 | 13 | Storage_EmbeddedFlash storage; 14 | 15 | static uint8_t page_buffer[FLASH_PAGE_SIZE]; 16 | 17 | void Storage_EmbeddedFlash::write_page_bytes(const uint32_t page, const uint32_t addr, const uint8_t *pdata, 18 | const uint32_t count) { 19 | if (count == 0) return; 20 | 21 | // 读出当前页数据 22 | for (uint32_t i = 0; i < FLASH_PAGE_SIZE; i++) { 23 | page_buffer[i] = *reinterpret_cast(FLASH_BASE + page * FLASH_PAGE_SIZE + i); 24 | } 25 | 26 | for (uint32_t i = 0; i < count; i++) { 27 | page_buffer[addr + i] = pdata[i]; 28 | } 29 | 30 | HAL_FLASH_Unlock(); //解锁Flash 31 | 32 | FLASH_EraseInitTypeDef EraseInitStruct; 33 | EraseInitStruct.TypeErase = FLASH_TYPEERASE_PAGES; //标明Flash执行页面只做擦除操作 34 | EraseInitStruct.Banks = FLASH_BANK_1; 35 | EraseInitStruct.Page = page; //声明要擦除的地址 36 | EraseInitStruct.NbPages = 1; //说明要擦除的页数,此参数必须是Min_Data = 1和Max_Data =(最大页数-初始页的值)之间的值 37 | uint32_t PageError = 0; //设置PageError,如果出现错误这个变量会被设置为出错的FLASH地址 38 | HAL_FLASHEx_Erase(&EraseInitStruct, &PageError); //调用擦除函数擦除 39 | 40 | for (uint32_t i = 0; i < FLASH_PAGE_SIZE / 8; i++) { 41 | while (HAL_OK != HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD, 42 | FLASH_BASE + page * FLASH_PAGE_SIZE + i * 8, 43 | *reinterpret_cast(page_buffer + i * 8))) {} 44 | } 45 | 46 | HAL_FLASH_Lock(); //锁住Flash 47 | } 48 | 49 | void Storage_EmbeddedFlash::write(const uint32_t addr, uint8_t *buff, const uint32_t count) { 50 | uint32_t start_page = (STORAGE_ADDRESS_BASE + addr - FLASH_BASE) / FLASH_PAGE_SIZE; 51 | uint32_t end_page = (STORAGE_ADDRESS_BASE + addr + count - FLASH_BASE) / FLASH_PAGE_SIZE; 52 | uint32_t page_num = end_page - start_page + 1; 53 | uint32_t offset = addr % FLASH_PAGE_SIZE; 54 | if (page_num == 1) { 55 | write_page_bytes(start_page, offset, buff, count); 56 | } else { 57 | for (uint32_t i = 0; i < page_num; i++) { 58 | if (i == 0) 59 | write_page_bytes(start_page, offset, buff, FLASH_PAGE_SIZE - offset); 60 | else if (i == page_num - 1) 61 | write_page_bytes(start_page + i, 0, buff + FLASH_PAGE_SIZE * i - offset, 62 | count + offset - FLASH_PAGE_SIZE * i); 63 | else 64 | write_page_bytes(start_page + i, 0, buff + FLASH_PAGE_SIZE * i - offset, FLASH_PAGE_SIZE); 65 | } 66 | } 67 | } 68 | 69 | void Storage_EmbeddedFlash::read(const uint32_t addr, uint8_t *buff, const uint32_t count) { 70 | auto s = reinterpret_cast(STORAGE_ADDRESS_BASE + addr); 71 | for (uint16_t i = 0; i < count; i++) { 72 | *(buff++) = *(s++); 73 | } 74 | } 75 | -------------------------------------------------------------------------------- /USB_Device/App/usbd_cdc_if.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usbd_cdc_if.h 5 | * @version : v3.0_Cube 6 | * @brief : Header for usbd_cdc_if.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2025 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 | 23 | #ifndef __USBD_CDC_IF_H__ 24 | #define __USBD_CDC_IF_H__ 25 | 26 | #ifdef __cplusplus 27 | extern "C" { 28 | #endif 29 | 30 | /* Includes ------------------------------------------------------------------*/ 31 | #include "usbd_cdc.h" 32 | 33 | /* USER CODE BEGIN INCLUDE */ 34 | 35 | /* USER CODE END INCLUDE */ 36 | 37 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 38 | * @brief For Usb device. 39 | * @{ 40 | */ 41 | 42 | /** @defgroup USBD_CDC_IF USBD_CDC_IF 43 | * @brief Usb VCP device module 44 | * @{ 45 | */ 46 | 47 | /** @defgroup USBD_CDC_IF_Exported_Defines USBD_CDC_IF_Exported_Defines 48 | * @brief Defines. 49 | * @{ 50 | */ 51 | /* Define size for the receive and transmit buffer over CDC */ 52 | #define APP_RX_DATA_SIZE 256 53 | #define APP_TX_DATA_SIZE 64 54 | /* USER CODE BEGIN EXPORTED_DEFINES */ 55 | 56 | /* USER CODE END EXPORTED_DEFINES */ 57 | 58 | /** 59 | * @} 60 | */ 61 | 62 | /** @defgroup USBD_CDC_IF_Exported_Types USBD_CDC_IF_Exported_Types 63 | * @brief Types. 64 | * @{ 65 | */ 66 | 67 | /* USER CODE BEGIN EXPORTED_TYPES */ 68 | 69 | /* USER CODE END EXPORTED_TYPES */ 70 | 71 | /** 72 | * @} 73 | */ 74 | 75 | /** @defgroup USBD_CDC_IF_Exported_Macros USBD_CDC_IF_Exported_Macros 76 | * @brief Aliases. 77 | * @{ 78 | */ 79 | 80 | /* USER CODE BEGIN EXPORTED_MACRO */ 81 | 82 | /* USER CODE END EXPORTED_MACRO */ 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | /** @defgroup USBD_CDC_IF_Exported_Variables USBD_CDC_IF_Exported_Variables 89 | * @brief Public variables. 90 | * @{ 91 | */ 92 | 93 | /** CDC Interface callback. */ 94 | extern USBD_CDC_ItfTypeDef USBD_Interface_fops_FS; 95 | 96 | /* USER CODE BEGIN EXPORTED_VARIABLES */ 97 | 98 | /* USER CODE END EXPORTED_VARIABLES */ 99 | 100 | /** 101 | * @} 102 | */ 103 | 104 | /** @defgroup USBD_CDC_IF_Exported_FunctionsPrototype USBD_CDC_IF_Exported_FunctionsPrototype 105 | * @brief Public functions declaration. 106 | * @{ 107 | */ 108 | 109 | uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len); 110 | 111 | /* USER CODE BEGIN EXPORTED_FUNCTIONS */ 112 | 113 | /* USER CODE END EXPORTED_FUNCTIONS */ 114 | 115 | /** 116 | * @} 117 | */ 118 | 119 | /** 120 | * @} 121 | */ 122 | 123 | /** 124 | * @} 125 | */ 126 | 127 | #ifdef __cplusplus 128 | } 129 | #endif 130 | 131 | #endif /* __USBD_CDC_IF_H__ */ 132 | 133 | -------------------------------------------------------------------------------- /USB_Device/App/usbd_desc.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usbd_desc.c 5 | * @version : v3.0_Cube 6 | * @brief : Header for usbd_conf.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2025 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 __USBD_DESC__C__ 23 | #define __USBD_DESC__C__ 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include "usbd_def.h" 31 | 32 | /* USER CODE BEGIN INCLUDE */ 33 | 34 | /* USER CODE END INCLUDE */ 35 | 36 | /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY 37 | * @{ 38 | */ 39 | 40 | /** @defgroup USBD_DESC USBD_DESC 41 | * @brief Usb device descriptors module. 42 | * @{ 43 | */ 44 | 45 | /** @defgroup USBD_DESC_Exported_Constants USBD_DESC_Exported_Constants 46 | * @brief Constants. 47 | * @{ 48 | */ 49 | #define DEVICE_ID1 (UID_BASE) 50 | #define DEVICE_ID2 (UID_BASE + 0x4) 51 | #define DEVICE_ID3 (UID_BASE + 0x8) 52 | 53 | #define USB_SIZ_STRING_SERIAL 0x1A 54 | 55 | /* USER CODE BEGIN EXPORTED_CONSTANTS */ 56 | 57 | /* USER CODE END EXPORTED_CONSTANTS */ 58 | 59 | /** 60 | * @} 61 | */ 62 | 63 | /** @defgroup USBD_DESC_Exported_Defines USBD_DESC_Exported_Defines 64 | * @brief Defines. 65 | * @{ 66 | */ 67 | 68 | /* USER CODE BEGIN EXPORTED_DEFINES */ 69 | 70 | /* USER CODE END EXPORTED_DEFINES */ 71 | 72 | /** 73 | * @} 74 | */ 75 | 76 | /** @defgroup USBD_DESC_Exported_TypesDefinitions USBD_DESC_Exported_TypesDefinitions 77 | * @brief Types. 78 | * @{ 79 | */ 80 | 81 | /* USER CODE BEGIN EXPORTED_TYPES */ 82 | 83 | /* USER CODE END EXPORTED_TYPES */ 84 | 85 | /** 86 | * @} 87 | */ 88 | 89 | /** @defgroup USBD_DESC_Exported_Macros USBD_DESC_Exported_Macros 90 | * @brief Aliases. 91 | * @{ 92 | */ 93 | 94 | /* USER CODE BEGIN EXPORTED_MACRO */ 95 | 96 | /* USER CODE END EXPORTED_MACRO */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | /** @defgroup USBD_DESC_Exported_Variables USBD_DESC_Exported_Variables 103 | * @brief Public variables. 104 | * @{ 105 | */ 106 | 107 | extern USBD_DescriptorsTypeDef CDC_Desc; 108 | 109 | /* USER CODE BEGIN EXPORTED_VARIABLES */ 110 | 111 | /* USER CODE END EXPORTED_VARIABLES */ 112 | 113 | /** 114 | * @} 115 | */ 116 | 117 | /** @defgroup USBD_DESC_Exported_FunctionsPrototype USBD_DESC_Exported_FunctionsPrototype 118 | * @brief Public functions declaration. 119 | * @{ 120 | */ 121 | 122 | /* USER CODE BEGIN EXPORTED_FUNCTIONS */ 123 | 124 | /* USER CODE END EXPORTED_FUNCTIONS */ 125 | 126 | /** 127 | * @} 128 | */ 129 | 130 | /** 131 | * @} 132 | */ 133 | 134 | /** 135 | * @} 136 | */ 137 | 138 | #ifdef __cplusplus 139 | } 140 | #endif 141 | 142 | #endif /* __USBD_DESC__C__ */ 143 | 144 | -------------------------------------------------------------------------------- /Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_spi_ex.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file stm32g4xx_hal_spi_ex.c 4 | * @author MCD Application Team 5 | * @brief Extended SPI HAL module driver. 6 | * This file provides firmware functions to manage the following 7 | * SPI peripheral extended functionalities : 8 | * + IO operation functions 9 | * 10 | ****************************************************************************** 11 | * @attention 12 | * 13 | * Copyright (c) 2019 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 "stm32g4xx_hal.h" 25 | 26 | /** @addtogroup STM32G4xx_HAL_Driver 27 | * @{ 28 | */ 29 | 30 | /** @defgroup SPIEx SPIEx 31 | * @brief SPI Extended HAL module driver 32 | * @{ 33 | */ 34 | #ifdef HAL_SPI_MODULE_ENABLED 35 | 36 | /* Private typedef -----------------------------------------------------------*/ 37 | /* Private defines -----------------------------------------------------------*/ 38 | /** @defgroup SPIEx_Private_Constants SPIEx Private Constants 39 | * @{ 40 | */ 41 | #define SPI_FIFO_SIZE 4UL 42 | /** 43 | * @} 44 | */ 45 | 46 | /* Private macros ------------------------------------------------------------*/ 47 | /* Private variables ---------------------------------------------------------*/ 48 | /* Private function prototypes -----------------------------------------------*/ 49 | /* Exported functions --------------------------------------------------------*/ 50 | 51 | /** @defgroup SPIEx_Exported_Functions SPIEx Exported Functions 52 | * @{ 53 | */ 54 | 55 | /** @defgroup SPIEx_Exported_Functions_Group1 IO operation functions 56 | * @brief Data transfers functions 57 | * 58 | @verbatim 59 | ============================================================================== 60 | ##### IO operation functions ##### 61 | =============================================================================== 62 | [..] 63 | This subsection provides a set of extended functions to manage the SPI 64 | data transfers. 65 | 66 | (#) Rx data flush function: 67 | (++) HAL_SPIEx_FlushRxFifo() 68 | 69 | @endverbatim 70 | * @{ 71 | */ 72 | 73 | /** 74 | * @brief Flush the RX fifo. 75 | * @param hspi pointer to a SPI_HandleTypeDef structure that contains 76 | * the configuration information for the specified SPI module. 77 | * @retval HAL status 78 | */ 79 | HAL_StatusTypeDef HAL_SPIEx_FlushRxFifo(const SPI_HandleTypeDef *hspi) 80 | { 81 | __IO uint32_t tmpreg; 82 | uint8_t count = 0U; 83 | while ((hspi->Instance->SR & SPI_FLAG_FRLVL) != SPI_FRLVL_EMPTY) 84 | { 85 | count++; 86 | tmpreg = hspi->Instance->DR; 87 | UNUSED(tmpreg); /* To avoid GCC warning */ 88 | if (count == SPI_FIFO_SIZE) 89 | { 90 | return HAL_TIMEOUT; 91 | } 92 | } 93 | return HAL_OK; 94 | } 95 | 96 | /** 97 | * @} 98 | */ 99 | 100 | /** 101 | * @} 102 | */ 103 | 104 | #endif /* HAL_SPI_MODULE_ENABLED */ 105 | 106 | /** 107 | * @} 108 | */ 109 | 110 | /** 111 | * @} 112 | */ 113 | -------------------------------------------------------------------------------- /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) 2024 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_2LINES; 43 | hspi1.Init.DataSize = SPI_DATASIZE_8BIT; 44 | hspi1.Init.CLKPolarity = SPI_POLARITY_HIGH; 45 | hspi1.Init.CLKPhase = SPI_PHASE_2EDGE; 46 | hspi1.Init.NSS = SPI_NSS_SOFT; 47 | hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16; 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 = 7; 52 | hspi1.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE; 53 | hspi1.Init.NSSPMode = SPI_NSS_PULSE_DISABLE; 54 | if (HAL_SPI_Init(&hspi1) != HAL_OK) 55 | { 56 | Error_Handler(); 57 | } 58 | /* USER CODE BEGIN SPI1_Init 2 */ 59 | 60 | /* USER CODE END SPI1_Init 2 */ 61 | 62 | } 63 | 64 | void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle) 65 | { 66 | 67 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 68 | if(spiHandle->Instance==SPI1) 69 | { 70 | /* USER CODE BEGIN SPI1_MspInit 0 */ 71 | 72 | /* USER CODE END SPI1_MspInit 0 */ 73 | /* SPI1 clock enable */ 74 | __HAL_RCC_SPI1_CLK_ENABLE(); 75 | 76 | __HAL_RCC_GPIOA_CLK_ENABLE(); 77 | /**SPI1 GPIO Configuration 78 | PA5 ------> SPI1_SCK 79 | PA6 ------> SPI1_MISO 80 | PA7 ------> SPI1_MOSI 81 | */ 82 | GPIO_InitStruct.Pin = GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7; 83 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 84 | GPIO_InitStruct.Pull = GPIO_NOPULL; 85 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 86 | GPIO_InitStruct.Alternate = GPIO_AF5_SPI1; 87 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 88 | 89 | /* USER CODE BEGIN SPI1_MspInit 1 */ 90 | 91 | /* USER CODE END SPI1_MspInit 1 */ 92 | } 93 | } 94 | 95 | void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle) 96 | { 97 | 98 | if(spiHandle->Instance==SPI1) 99 | { 100 | /* USER CODE BEGIN SPI1_MspDeInit 0 */ 101 | 102 | /* USER CODE END SPI1_MspDeInit 0 */ 103 | /* Peripheral clock disable */ 104 | __HAL_RCC_SPI1_CLK_DISABLE(); 105 | 106 | /**SPI1 GPIO Configuration 107 | PA5 ------> SPI1_SCK 108 | PA6 ------> SPI1_MISO 109 | PA7 ------> SPI1_MOSI 110 | */ 111 | HAL_GPIO_DeInit(GPIOA, GPIO_PIN_5|GPIO_PIN_6|GPIO_PIN_7); 112 | 113 | /* USER CODE BEGIN SPI1_MspDeInit 1 */ 114 | 115 | /* USER CODE END SPI1_MspDeInit 1 */ 116 | } 117 | } 118 | 119 | /* USER CODE BEGIN 1 */ 120 | 121 | /* USER CODE END 1 */ 122 | -------------------------------------------------------------------------------- /Core/Src/syscalls.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file syscalls.c 4 | * @author Auto-generated by STM32CubeIDE 5 | * @brief STM32CubeIDE Minimal System calls file 6 | * 7 | * For more information about which c-functions 8 | * need which of these lowlevel functions 9 | * please consult the Newlib libc-manual 10 | ****************************************************************************** 11 | * @attention 12 | * 13 | * Copyright (c) 2020-2023 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 | 37 | extern int __io_getchar(void) __attribute__((weak)); 38 | 39 | 40 | char *__env[1] = {0}; 41 | char **environ = __env; 42 | 43 | 44 | /* Functions */ 45 | void initialise_monitor_handles() { 46 | } 47 | 48 | int _getpid(void) { 49 | return 1; 50 | } 51 | 52 | int _kill(int pid, int sig) { 53 | (void) pid; 54 | (void) sig; 55 | errno = EINVAL; 56 | return -1; 57 | } 58 | 59 | void _exit(int status) { 60 | _kill(status, -1); 61 | while (1) {} /* Make sure we hang here */ 62 | } 63 | 64 | __attribute__((weak)) int _read(int file, char *ptr, int len) { 65 | (void) file; 66 | int DataIdx; 67 | 68 | for (DataIdx = 0; DataIdx < len; DataIdx++) { 69 | *ptr++ = __io_getchar(); 70 | } 71 | 72 | return len; 73 | } 74 | 75 | __attribute__((weak)) int _write(int file, char *ptr, int len) { 76 | (void) file; 77 | int DataIdx; 78 | 79 | for (DataIdx = 0; DataIdx < len; DataIdx++) { 80 | __io_putchar(*ptr++); 81 | } 82 | return len; 83 | } 84 | 85 | int _open(char *path, int flags, ...) { 86 | (void) path; 87 | (void) flags; 88 | /* Pretend like we always fail */ 89 | return -1; 90 | } 91 | 92 | int _wait(int *status) { 93 | (void) status; 94 | errno = ECHILD; 95 | return -1; 96 | } 97 | 98 | int _unlink(char *name) { 99 | (void) name; 100 | errno = ENOENT; 101 | return -1; 102 | } 103 | 104 | int _times(struct tms *buf) { 105 | (void) buf; 106 | return -1; 107 | } 108 | 109 | int _stat(char *file, struct stat *st) { 110 | (void) file; 111 | st->st_mode = S_IFCHR; 112 | return 0; 113 | } 114 | 115 | int _link(char *old, char *new) { 116 | (void) old; 117 | (void) new; 118 | errno = EMLINK; 119 | return -1; 120 | } 121 | 122 | int _fork(void) { 123 | errno = EAGAIN; 124 | return -1; 125 | } 126 | 127 | int _execve(char *name, char **argv, char **env) { 128 | (void) name; 129 | (void) argv; 130 | (void) env; 131 | errno = ENOMEM; 132 | return -1; 133 | } 134 | // 135 | //int _close(int file) { 136 | // (void) file; 137 | // return -1; 138 | //} 139 | // 140 | // 141 | //int _fstat(int file, struct stat *st) { 142 | // (void) file; 143 | // st->st_mode = S_IFCHR; 144 | // return 0; 145 | //} 146 | // 147 | //int _isatty(int file) { 148 | // (void) file; 149 | // return 1; 150 | //} 151 | // 152 | //int _lseek(int file, int ptr, int dir) { 153 | // (void) file; 154 | // (void) ptr; 155 | // (void) dir; 156 | // return 0; 157 | //} -------------------------------------------------------------------------------- /UserLib/PID/PID.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @brief PID基础控制库(C++) 3 | * @details 4 | * @author Haoqi Liu 5 | * @date 2025-1-20 6 | * @version V1.1.0 7 | * @note 8 | * @warning 9 | * @par 历史版本 10 | * V1.0.0创建于2024-9-21,更改自C语言版本PID库 11 | * V1.1.0创建于2025-1-20,添加类初始化默认限幅参数,现在可以在初始化时设置限幅 12 | * */ 13 | 14 | #ifndef PID_H 15 | #define PID_H 16 | #include 17 | 18 | class PID { 19 | public: 20 | enum PID_type { 21 | position_type, //位置式PID 22 | delta_type, //增量式PID 23 | }; 24 | 25 | /** 26 | * @brief 不允许默认初始化,初始化必须要有PID种类,kp,ki,kd参数 27 | * */ 28 | PID() = delete; 29 | 30 | /** 31 | * @brief PID结构体初始化函数 32 | * @param PID_type PID类型 33 | * @param kp,ki,kd PID三个参数 34 | * @param sum_error_limit_p 积分限幅上限 35 | * @param sum_error_limit_n 积分限幅下限 36 | * @param output_limit_p 输出限幅上限 37 | * @param output_limit_n 输出限幅下限 38 | * */ 39 | PID(const PID_type PID_type, const float kp, const float ki, const float kd, 40 | const float sum_error_limit_p = NAN, const float sum_error_limit_n = NAN, 41 | const float output_limit_p = NAN, const float output_limit_n = NAN) 42 | : PID_type(PID_type), kp(kp), ki(ki), kd(kd), 43 | sum_error_limit_p(sum_error_limit_p), sum_error_limit_n(sum_error_limit_n), 44 | output_limit_p(output_limit_p), output_limit_n(output_limit_n) {} 45 | 46 | /** 47 | * @brief 设置PID目标值 48 | * @param Target 新的PID目标值 49 | * */ 50 | void SetTarget(const float Target) { target = Target; } 51 | 52 | /** 53 | * @brief 设置积分值,用于高自由度的积分限幅 54 | * @param sum_error PID积分值 55 | */ 56 | void set_sum_error(const float sum_error) { PID::sum_error = sum_error; } 57 | 58 | /** 59 | * @brief PID计算 60 | * @param input PID观测值 61 | * @return PID计算结果 62 | * */ 63 | [[nodiscard]] float calc(float input); 64 | 65 | /*设置参数*/ 66 | float target{0}; //目标值 67 | PID_type PID_type; //PID种类,位置式或增量式 68 | float kp, ki, kd; //比例、积分、微分系数 69 | 70 | /*限幅参数*/ 71 | float sum_error_limit_p{NAN}; //积分限幅上限,仅位置式有效 72 | float sum_error_limit_n{NAN}; //积分限幅下限,仅位置式有效 73 | float output_limit_p{NAN}; //输出限幅上限 74 | float output_limit_n{NAN}; //输出限幅下限 75 | private: 76 | /*中间(运行时)变量*/ 77 | float error{0}; //上一次的偏差值 78 | float pre_error{0}; //上上一次的偏差值,仅增量式PID使用 79 | float sum_error{0}; //累计偏差值,仅位置式PID使用 80 | float output{0}; //PID输出值 81 | }; 82 | 83 | inline float PID::calc(const float input) { 84 | const float error_ = target - input; 85 | if (PID_type == position_type) { 86 | /***位置式PID公式:u=Kpe(t)+Ki*e(t)的积分+Kd[e(t)-e(t-1)]***/ 87 | sum_error += error_; 88 | /*积分限幅*/ 89 | if (!std::isnan(sum_error_limit_p)) 90 | if (sum_error >= sum_error_limit_p) sum_error = sum_error_limit_p; 91 | if (!std::isnan(sum_error_limit_n)) 92 | if (sum_error <= sum_error_limit_n) sum_error = sum_error_limit_n; 93 | output = kp * error_ + 94 | ki * sum_error + 95 | kd * (error_ - error); 96 | error = error_; 97 | } else if (PID_type == delta_type) { 98 | /***增量式PID公式:du=Kp[e(t)-e(t-1)]+Kie(t)+Kd[e(t)-2e(t-1)+e(t-2)]***/ 99 | output += kp * (error_ - error) + 100 | ki * (error_) + 101 | kd * (error_ - 2 * error + pre_error); 102 | pre_error = error; 103 | error = error_; 104 | } 105 | /*输出限幅*/ 106 | if (!std::isnan(output_limit_p)) 107 | if (output >= output_limit_p) output = output_limit_p; 108 | if (!std::isnan(output_limit_n)) 109 | if (output <= output_limit_n) output = output_limit_n; 110 | 111 | return output; 112 | } 113 | 114 | #endif //PID_H 115 | -------------------------------------------------------------------------------- /UserLib/LetterShell/Src/shell_cmd_list.c: -------------------------------------------------------------------------------- 1 | /** 2 | * @file shell_cmd_list.c 3 | * @author Letter (NevermindZZT@gmail.com) 4 | * @brief shell cmd list 5 | * @version 3.0.0 6 | * @date 2020-01-17 7 | * 8 | * @copyright (c) 2020 Letter 9 | * 10 | */ 11 | 12 | #include "shell.h" 13 | 14 | #if SHELL_USING_CMD_EXPORT != 1 15 | 16 | extern int shellSetVar(char *name, int value); 17 | extern void shellUp(Shell *shell); 18 | extern void shellDown(Shell *shell); 19 | extern void shellRight(Shell *shell); 20 | extern void shellLeft(Shell *shell); 21 | extern void shellTab(Shell *shell); 22 | extern void shellBackspace(Shell *shell); 23 | extern void shellDelete(Shell *shell); 24 | extern void shellEnter(Shell *shell); 25 | extern void shellHelp(int argc, char *argv[]); 26 | extern void shellUsers(void); 27 | extern void shellCmds(void); 28 | extern void shellVars(void); 29 | extern void shellKeys(void); 30 | extern void shellClear(void); 31 | #if SHELL_EXEC_UNDEF_FUNC == 1 32 | extern int shellExecute(int argc, char *argv[]); 33 | #endif 34 | 35 | SHELL_AGENCY_FUNC(shellRun, shellGetCurrent(), (const char *)p1); 36 | 37 | 38 | /** 39 | * @brief shell命令表 40 | * 41 | */ 42 | const ShellCommand shellCommandList[] = 43 | { 44 | {.attr.value=SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_USER), 45 | .data.user.name = SHELL_DEFAULT_USER, 46 | .data.user.password = SHELL_DEFAULT_USER_PASSWORD, 47 | .data.user.desc = "default user"}, 48 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC), 49 | setVar, shellSetVar, set var), 50 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0), 0x1B5B4100, shellUp, up), 51 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0), 0x1B5B4200, shellDown, down), 52 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 53 | 0x1B5B4300, shellRight, right), 54 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 55 | 0x1B5B4400, shellLeft, left), 56 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0), 0x09000000, shellTab, tab), 57 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 58 | 0x08000000, shellBackspace, backspace), 59 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 60 | 0x7F000000, shellDelete, delete), 61 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 62 | 0x1B5B337E, shellDelete, delete), 63 | #if SHELL_ENTER_LF == 1 64 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 65 | 0x0A000000, shellEnter, enter), 66 | #endif 67 | #if SHELL_ENTER_CR == 1 68 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 69 | 0x0D000000, shellEnter, enter), 70 | #endif 71 | #if SHELL_ENTER_CRLF == 1 72 | SHELL_KEY_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_ENABLE_UNCHECKED, 73 | 0x0D0A0000, shellEnter, enter), 74 | #endif 75 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_DISABLE_RETURN, 76 | help, shellHelp, show command info\r\nhelp [cmd]), 77 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 78 | users, shellUsers, list all user), 79 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 80 | cmds, shellCmds, list all cmd), 81 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 82 | vars, shellVars, list all var), 83 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 84 | keys, shellKeys, list all key), 85 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 86 | clear, shellClear, clear console), 87 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_DISABLE_RETURN, 88 | sh, SHELL_AGENCY_FUNC_NAME(shellRun), run command directly), 89 | #if SHELL_EXEC_UNDEF_FUNC == 1 90 | SHELL_CMD_ITEM(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_MAIN)|SHELL_CMD_DISABLE_RETURN, 91 | exec, shellExecute, execute function undefined), 92 | #endif 93 | }; 94 | 95 | 96 | /** 97 | * @brief shell命令表大小 98 | * 99 | */ 100 | const unsigned short shellCommandCount 101 | = sizeof(shellCommandList) / sizeof(ShellCommand); 102 | 103 | #endif 104 | -------------------------------------------------------------------------------- /Core/Src/fdcan.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file fdcan.c 5 | * @brief This file provides code for the configuration 6 | * of the FDCAN instances. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2024 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 "fdcan.h" 22 | 23 | /* USER CODE BEGIN 0 */ 24 | 25 | /* USER CODE END 0 */ 26 | 27 | FDCAN_HandleTypeDef hfdcan1; 28 | 29 | /* FDCAN1 init function */ 30 | void MX_FDCAN1_Init(void) 31 | { 32 | 33 | /* USER CODE BEGIN FDCAN1_Init 0 */ 34 | 35 | /* USER CODE END FDCAN1_Init 0 */ 36 | 37 | /* USER CODE BEGIN FDCAN1_Init 1 */ 38 | 39 | /* USER CODE END FDCAN1_Init 1 */ 40 | hfdcan1.Instance = FDCAN1; 41 | hfdcan1.Init.ClockDivider = FDCAN_CLOCK_DIV1; 42 | hfdcan1.Init.FrameFormat = FDCAN_FRAME_CLASSIC; 43 | hfdcan1.Init.Mode = FDCAN_MODE_NORMAL; 44 | hfdcan1.Init.AutoRetransmission = ENABLE; 45 | hfdcan1.Init.TransmitPause = DISABLE; 46 | hfdcan1.Init.ProtocolException = DISABLE; 47 | hfdcan1.Init.NominalPrescaler = 10; 48 | hfdcan1.Init.NominalSyncJumpWidth = 1; 49 | hfdcan1.Init.NominalTimeSeg1 = 8; 50 | hfdcan1.Init.NominalTimeSeg2 = 8; 51 | hfdcan1.Init.DataPrescaler = 1; 52 | hfdcan1.Init.DataSyncJumpWidth = 1; 53 | hfdcan1.Init.DataTimeSeg1 = 1; 54 | hfdcan1.Init.DataTimeSeg2 = 1; 55 | hfdcan1.Init.StdFiltersNbr = 1; 56 | hfdcan1.Init.ExtFiltersNbr = 0; 57 | hfdcan1.Init.TxFifoQueueMode = FDCAN_TX_FIFO_OPERATION; 58 | if (HAL_FDCAN_Init(&hfdcan1) != HAL_OK) 59 | { 60 | Error_Handler(); 61 | } 62 | /* USER CODE BEGIN FDCAN1_Init 2 */ 63 | 64 | /* USER CODE END FDCAN1_Init 2 */ 65 | 66 | } 67 | 68 | void HAL_FDCAN_MspInit(FDCAN_HandleTypeDef* fdcanHandle) 69 | { 70 | 71 | GPIO_InitTypeDef GPIO_InitStruct = {0}; 72 | RCC_PeriphCLKInitTypeDef PeriphClkInit = {0}; 73 | if(fdcanHandle->Instance==FDCAN1) 74 | { 75 | /* USER CODE BEGIN FDCAN1_MspInit 0 */ 76 | 77 | /* USER CODE END FDCAN1_MspInit 0 */ 78 | 79 | /** Initializes the peripherals clocks 80 | */ 81 | PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_FDCAN; 82 | PeriphClkInit.FdcanClockSelection = RCC_FDCANCLKSOURCE_PCLK1; 83 | if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK) 84 | { 85 | Error_Handler(); 86 | } 87 | 88 | /* FDCAN1 clock enable */ 89 | __HAL_RCC_FDCAN_CLK_ENABLE(); 90 | 91 | __HAL_RCC_GPIOB_CLK_ENABLE(); 92 | /**FDCAN1 GPIO Configuration 93 | PB8-BOOT0 ------> FDCAN1_RX 94 | PB9 ------> FDCAN1_TX 95 | */ 96 | GPIO_InitStruct.Pin = GPIO_PIN_8|GPIO_PIN_9; 97 | GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; 98 | GPIO_InitStruct.Pull = GPIO_NOPULL; 99 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 100 | GPIO_InitStruct.Alternate = GPIO_AF9_FDCAN1; 101 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 102 | 103 | /* FDCAN1 interrupt Init */ 104 | HAL_NVIC_SetPriority(FDCAN1_IT0_IRQn, 5, 0); 105 | HAL_NVIC_EnableIRQ(FDCAN1_IT0_IRQn); 106 | HAL_NVIC_SetPriority(FDCAN1_IT1_IRQn, 5, 0); 107 | HAL_NVIC_EnableIRQ(FDCAN1_IT1_IRQn); 108 | /* USER CODE BEGIN FDCAN1_MspInit 1 */ 109 | 110 | /* USER CODE END FDCAN1_MspInit 1 */ 111 | } 112 | } 113 | 114 | void HAL_FDCAN_MspDeInit(FDCAN_HandleTypeDef* fdcanHandle) 115 | { 116 | 117 | if(fdcanHandle->Instance==FDCAN1) 118 | { 119 | /* USER CODE BEGIN FDCAN1_MspDeInit 0 */ 120 | 121 | /* USER CODE END FDCAN1_MspDeInit 0 */ 122 | /* Peripheral clock disable */ 123 | __HAL_RCC_FDCAN_CLK_DISABLE(); 124 | 125 | /**FDCAN1 GPIO Configuration 126 | PB8-BOOT0 ------> FDCAN1_RX 127 | PB9 ------> FDCAN1_TX 128 | */ 129 | HAL_GPIO_DeInit(GPIOB, GPIO_PIN_8|GPIO_PIN_9); 130 | 131 | /* FDCAN1 interrupt Deinit */ 132 | HAL_NVIC_DisableIRQ(FDCAN1_IT0_IRQn); 133 | HAL_NVIC_DisableIRQ(FDCAN1_IT1_IRQn); 134 | /* USER CODE BEGIN FDCAN1_MspDeInit 1 */ 135 | 136 | /* USER CODE END FDCAN1_MspDeInit 1 */ 137 | } 138 | } 139 | 140 | /* USER CODE BEGIN 1 */ 141 | 142 | /* USER CODE END 1 */ 143 | -------------------------------------------------------------------------------- /USB_Device/Target/usbd_conf.h: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * @file : usbd_conf.h 5 | * @version : v3.0_Cube 6 | * @brief : Header for usbd_conf.c file. 7 | ****************************************************************************** 8 | * @attention 9 | * 10 | * Copyright (c) 2025 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 __USBD_CONF__H__ 23 | #define __USBD_CONF__H__ 24 | 25 | #ifdef __cplusplus 26 | extern "C" { 27 | #endif 28 | 29 | /* Includes ------------------------------------------------------------------*/ 30 | #include 31 | #include 32 | #include 33 | #include "stm32g4xx.h" 34 | #include "stm32g4xx_hal.h" 35 | 36 | /* USER CODE BEGIN INCLUDE */ 37 | 38 | /* USER CODE END INCLUDE */ 39 | 40 | /** @addtogroup USBD_OTG_DRIVER 41 | * @brief Driver for Usb device. 42 | * @{ 43 | */ 44 | 45 | /** @defgroup USBD_CONF USBD_CONF 46 | * @brief Configuration file for Usb otg low level driver. 47 | * @{ 48 | */ 49 | 50 | /** @defgroup USBD_CONF_Exported_Variables USBD_CONF_Exported_Variables 51 | * @brief Public variables. 52 | * @{ 53 | */ 54 | 55 | /* Private variables ---------------------------------------------------------*/ 56 | /* USER CODE BEGIN PV */ 57 | /* USER CODE END PV */ 58 | /** 59 | * @} 60 | */ 61 | 62 | /** @defgroup USBD_CONF_Exported_Defines USBD_CONF_Exported_Defines 63 | * @brief Defines for configuration of the Usb device. 64 | * @{ 65 | */ 66 | 67 | /*---------- -----------*/ 68 | #define USBD_MAX_NUM_INTERFACES 1U 69 | /*---------- -----------*/ 70 | #define USBD_MAX_NUM_CONFIGURATION 1U 71 | /*---------- -----------*/ 72 | #define USBD_MAX_STR_DESC_SIZ 512U 73 | /*---------- -----------*/ 74 | #define USBD_DEBUG_LEVEL 0U 75 | /*---------- -----------*/ 76 | #define USBD_LPM_ENABLED 1U 77 | /*---------- -----------*/ 78 | #define USBD_SELF_POWERED 1U 79 | 80 | /****************************************/ 81 | /* #define for FS and HS identification */ 82 | #define DEVICE_FS 0 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | /** @defgroup USBD_CONF_Exported_Macros USBD_CONF_Exported_Macros 89 | * @brief Aliases. 90 | * @{ 91 | */ 92 | 93 | /* Memory management macros */ 94 | 95 | /** Alias for memory allocation. */ 96 | #define USBD_malloc (void *)USBD_static_malloc 97 | 98 | /** Alias for memory release. */ 99 | #define USBD_free USBD_static_free 100 | 101 | /** Alias for memory set. */ 102 | #define USBD_memset memset 103 | 104 | /** Alias for memory copy. */ 105 | #define USBD_memcpy memcpy 106 | 107 | /** Alias for delay. */ 108 | #define USBD_Delay HAL_Delay 109 | 110 | /* DEBUG macros */ 111 | 112 | #if (USBD_DEBUG_LEVEL > 0) 113 | #define USBD_UsrLog(...) printf(__VA_ARGS__);\ 114 | printf("\n"); 115 | #else 116 | #define USBD_UsrLog(...) 117 | #endif 118 | 119 | #if (USBD_DEBUG_LEVEL > 1) 120 | 121 | #define USBD_ErrLog(...) printf("ERROR: ") ;\ 122 | printf(__VA_ARGS__);\ 123 | printf("\n"); 124 | #else 125 | #define USBD_ErrLog(...) 126 | #endif 127 | 128 | #if (USBD_DEBUG_LEVEL > 2) 129 | #define USBD_DbgLog(...) printf("DEBUG : ") ;\ 130 | printf(__VA_ARGS__);\ 131 | printf("\n"); 132 | #else 133 | #define USBD_DbgLog(...) 134 | #endif 135 | 136 | /** 137 | * @} 138 | */ 139 | 140 | /** @defgroup USBD_CONF_Exported_Types USBD_CONF_Exported_Types 141 | * @brief Types. 142 | * @{ 143 | */ 144 | 145 | /** 146 | * @} 147 | */ 148 | 149 | /** @defgroup USBD_CONF_Exported_FunctionsPrototype USBD_CONF_Exported_FunctionsPrototype 150 | * @brief Declaration of public functions for Usb device. 151 | * @{ 152 | */ 153 | 154 | /* Exported functions -------------------------------------------------------*/ 155 | void *USBD_static_malloc(uint32_t size); 156 | void USBD_static_free(void *p); 157 | 158 | /** 159 | * @} 160 | */ 161 | 162 | /** 163 | * @} 164 | */ 165 | 166 | /** 167 | * @} 168 | */ 169 | 170 | #ifdef __cplusplus 171 | } 172 | #endif 173 | 174 | #endif /* __USBD_CONF__H__ */ 175 | 176 | -------------------------------------------------------------------------------- /Applications/Src/CommunicateTask.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Created by 26757 on 25-5-6. 3 | // 4 | #include 5 | #include "task_public.h" 6 | #include "fdcan.h" 7 | #include "FOC.h" 8 | #include "queue.h" 9 | #include "task.h" 10 | 11 | using namespace std; 12 | 13 | extern FOC foc; 14 | 15 | void FDCAN_Filter_INIT(FDCAN_HandleTypeDef *hfdcan); 16 | void CAN_Transmit(uint8_t length, uint8_t *pdata); 17 | void FeedBackSend(); 18 | 19 | xQueueHandle xQueue1; 20 | 21 | void StartCommunicateTask(void *argument) { 22 | xQueue1 = xQueueCreate(5, 3); 23 | // 1.等待foc初始化 24 | while (!foc.initialized) 25 | delay(100); 26 | foc.enable(); // 使能FOC 27 | foc.anticogging_enabled = false; 28 | // 2.初始化CAN并开启CAN接收 29 | FDCAN_Filter_INIT(&hfdcan1); 30 | 31 | uint8_t RxBuffer[3]; 32 | while (true) { 33 | xQueueReceive(xQueue1, &RxBuffer, portMAX_DELAY); 34 | 35 | switch (RxBuffer[0]) { 36 | case 0x00: // NOP指令,只发送反馈报文 37 | break; 38 | case 0x01: // 使能指令 39 | foc.start(); 40 | if (foc.started) 41 | HAL_GPIO_WritePin(LED_G_GPIO_Port, LED_G_Pin, GPIO_PIN_RESET); 42 | break; 43 | case 0x02: // 失能指令 44 | foc.stop(); 45 | HAL_GPIO_WritePin(LED_G_GPIO_Port, LED_G_Pin, GPIO_PIN_SET); 46 | break; 47 | case 0x03: // 电流控制 48 | foc.Ctrl(FOC::CtrlType::CurrentCtrl, 49 | *(int16_t *)(RxBuffer + 1) * 10.0f / INT16_MAX); 50 | break; 51 | case 0x04: // 速度控制 52 | foc.Ctrl(FOC::CtrlType::SpeedCtrl, 53 | *(int16_t *)(RxBuffer + 1) * 1000.0f / INT16_MAX); 54 | break; 55 | case 0x05: // 角度控制 56 | foc.Ctrl(FOC::CtrlType::AngleCtrl, 57 | *(int16_t *)(RxBuffer + 1) * 2 * numbers::pi_v / UINT16_MAX); 58 | break; 59 | case 0x06: // 角度控制 60 | foc.Ctrl(FOC::CtrlType::LowSpeedCtrl, 61 | *(int16_t *)(RxBuffer + 1) * 1000.0f / INT16_MAX); 62 | break; 63 | default: 64 | break; 65 | } 66 | if (RxBuffer[0] <= 0x06) { 67 | // 是合法命令则发送反馈报文 68 | FeedBackSend(); 69 | } 70 | } 71 | } 72 | 73 | /** 74 | * @brief CAN外设初始化函数 75 | * */ 76 | void FDCAN_Filter_INIT(FDCAN_HandleTypeDef *hfdcan) { 77 | FDCAN_FilterTypeDef Filter; 78 | Filter.IdType = FDCAN_STANDARD_ID; 79 | Filter.FilterIndex = 0; 80 | Filter.FilterType = FDCAN_FILTER_RANGE; 81 | Filter.FilterConfig = FDCAN_FILTER_TO_RXFIFO0; 82 | Filter.FilterID1 = 0x400; 83 | Filter.FilterID2 = 0x40F; 84 | 85 | HAL_FDCAN_ConfigFilter(hfdcan, &Filter); 86 | HAL_FDCAN_ConfigGlobalFilter(hfdcan, FDCAN_REJECT, FDCAN_REJECT, FDCAN_FILTER_REMOTE, FDCAN_FILTER_REMOTE); 87 | HAL_FDCAN_Start(hfdcan); 88 | HAL_FDCAN_ActivateNotification(hfdcan, FDCAN_IT_RX_FIFO0_NEW_MESSAGE, 0); 89 | } 90 | 91 | /** 92 | * @brief CAN接收回调函数 93 | * */ 94 | void HAL_FDCAN_RxFifo0Callback(FDCAN_HandleTypeDef *hfdcan, uint32_t RxFifo0ITs) { 95 | BaseType_t xHigherPriorityTaskWoken; 96 | if (hfdcan == &hfdcan1) { 97 | FDCAN_RxHeaderTypeDef RxHeader; 98 | uint8_t FDCAN_RxData[3]; 99 | /*如果FIFO中有数据*/ 100 | if (HAL_FDCAN_GetRxFifoFillLevel(hfdcan, FDCAN_RX_FIFO0)) { 101 | /*读取数据*/ 102 | HAL_FDCAN_GetRxMessage(hfdcan, FDCAN_RX_FIFO0, &RxHeader, FDCAN_RxData); 103 | if (RxHeader.Identifier == 0x400 + foc.ID && RxHeader.DataLength == 3) { 104 | // 如果是自己ID的报文,进行处理 105 | xQueueSendToBackFromISR(xQueue1, FDCAN_RxData, &xHigherPriorityTaskWoken); 106 | if (xHigherPriorityTaskWoken) { 107 | taskYIELD(); 108 | } 109 | } 110 | } 111 | } 112 | } 113 | 114 | void CAN_Transmit(uint8_t length, uint8_t *pdata) { 115 | /*定义CAN数据包头*/ 116 | static FDCAN_TxHeaderTypeDef TxHeader = { 117 | 0x500, FDCAN_STANDARD_ID, FDCAN_DATA_FRAME, FDCAN_DLC_BYTES_8, FDCAN_ESI_ACTIVE, 118 | FDCAN_BRS_OFF,FDCAN_CLASSIC_CAN, FDCAN_NO_TX_EVENTS, 0 119 | }; 120 | TxHeader.Identifier = 0x500 + foc.ID; 121 | TxHeader.DataLength = length; 122 | HAL_FDCAN_AddMessageToTxFifoQ(&hfdcan1, &TxHeader, pdata); 123 | } 124 | 125 | void FeedBackSend() { 126 | static uint8_t FeedBackDataBuffer[8] = {0}; 127 | // 电机状态 128 | FeedBackDataBuffer[0] = foc.started; 129 | // 错误码(预留) 130 | FeedBackDataBuffer[1] = 0x00; 131 | // Q轴电流 132 | *(int16_t *)(FeedBackDataBuffer + 2) = foc.getCurrent() / 10 * INT16_MAX; 133 | // 电机转速 134 | *(int16_t *)(FeedBackDataBuffer + 4) = foc.getSpeed() / 1000 * INT16_MAX; 135 | // 电机角度 136 | *(int16_t *)(FeedBackDataBuffer + 6) = foc.getAngle() / (2 * numbers::pi_v) * UINT16_MAX; 137 | CAN_Transmit(8, FeedBackDataBuffer); 138 | } 139 | -------------------------------------------------------------------------------- /BSP/retarget/printf.h: -------------------------------------------------------------------------------- 1 | /////////////////////////////////////////////////////////////////////////////// 2 | // \author (c) Marco Paland (info@paland.com) 3 | // 2014-2019, PALANDesign Hannover, Germany 4 | // 5 | // \license The MIT License (MIT) 6 | // 7 | // Permission is hereby granted, free of charge, to any person obtaining a copy 8 | // of this software and associated documentation files (the "Software"), to deal 9 | // in the Software without restriction, including without limitation the rights 10 | // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 11 | // copies of the Software, and to permit persons to whom the Software is 12 | // furnished to do so, subject to the following conditions: 13 | // 14 | // The above copyright notice and this permission notice shall be included in 15 | // all copies or substantial portions of the Software. 16 | // 17 | // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 18 | // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 19 | // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 20 | // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 21 | // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 22 | // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 23 | // THE SOFTWARE. 24 | // 25 | // \brief Tiny printf, sprintf and snprintf implementation, optimized for speed on 26 | // embedded systems with a very limited resources. 27 | // Use this instead of bloated standard/newlib printf. 28 | // These routines are thread safe and reentrant. 29 | // 30 | /////////////////////////////////////////////////////////////////////////////// 31 | 32 | #ifndef _PRINTF_H_ 33 | #define _PRINTF_H_ 34 | 35 | #ifdef __cplusplus 36 | extern "C" { 37 | #endif 38 | 39 | #include 40 | #include 41 | 42 | /** 43 | * Output a character to a custom device like UART, used by the printf() function 44 | * This function is declared here only. You have to write your custom implementation somewhere 45 | * \param character Character to output 46 | */ 47 | void _putchar(char character); 48 | 49 | 50 | /** 51 | * Tiny printf implementation 52 | * You have to implement _putchar if you use printf() 53 | * To avoid conflicts with the regular printf() API it is overridden by macro defines 54 | * and internal underscore-appended functions like printf_() are used 55 | * \param format A string that specifies the format of the output 56 | * \return The number of characters that are written into the array, not counting the terminating null character 57 | */ 58 | #define printf printf_ 59 | 60 | int printf_(const char *format, ...); 61 | 62 | 63 | /** 64 | * Tiny sprintf implementation 65 | * Due to security reasons (buffer overflow) YOU SHOULD CONSIDER USING (V)SNPRINTF INSTEAD! 66 | * \param buffer A pointer to the buffer where to store the formatted string. MUST be big enough to store the output! 67 | * \param format A string that specifies the format of the output 68 | * \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character 69 | */ 70 | #define sprintf sprintf_ 71 | 72 | int sprintf_(char *buffer, const char *format, ...); 73 | 74 | 75 | /** 76 | * Tiny snprintf/vsnprintf implementation 77 | * \param buffer A pointer to the buffer where to store the formatted string 78 | * \param count The maximum number of characters to store in the buffer, including a terminating null character 79 | * \param format A string that specifies the format of the output 80 | * \param va A value identifying a variable arguments list 81 | * \return The number of characters that COULD have been written into the buffer, not counting the terminating 82 | * null character. A value equal or larger than count indicates truncation. Only when the returned value 83 | * is non-negative and less than count, the string has been completely written. 84 | */ 85 | #define snprintf snprintf_ 86 | #define vsnprintf vsnprintf_ 87 | 88 | int snprintf_(char *buffer, size_t count, const char *format, ...); 89 | 90 | int vsnprintf_(char *buffer, size_t count, const char *format, va_list va); 91 | 92 | 93 | /** 94 | * Tiny vprintf implementation 95 | * \param format A string that specifies the format of the output 96 | * \param va A value identifying a variable arguments list 97 | * \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character 98 | */ 99 | #define vprintf vprintf_ 100 | 101 | int vprintf_(const char *format, va_list va); 102 | 103 | 104 | /** 105 | * printf with output function 106 | * You may use this as dynamic alternative to printf() with its fixed _putchar() output 107 | * \param out An output function which takes one character and an argument pointer 108 | * \param arg An argument pointer for user data passed to output function 109 | * \param format A string that specifies the format of the output 110 | * \return The number of characters that are sent to the output function, not counting the terminating null character 111 | */ 112 | int fctprintf(void (*out)(char character, void *arg), void *arg, const char *format, ...); 113 | 114 | #ifdef __cplusplus 115 | }; 116 | #endif 117 | 118 | #endif // _PRINTF_H_ 119 | -------------------------------------------------------------------------------- /Core/Src/app_freertos.c: -------------------------------------------------------------------------------- 1 | /* USER CODE BEGIN Header */ 2 | /** 3 | ****************************************************************************** 4 | * File Name : app_freertos.c 5 | * Description : Code for freertos applications 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | * Copyright (c) 2024 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 "FreeRTOS.h" 22 | #include "task.h" 23 | #include "main.h" 24 | #include "cmsis_os.h" 25 | 26 | #include "usb_device.h" 27 | 28 | /* Private includes ----------------------------------------------------------*/ 29 | /* USER CODE BEGIN Includes */ 30 | #include "task_public.h" 31 | /* USER CODE END Includes */ 32 | 33 | /* Private typedef -----------------------------------------------------------*/ 34 | /* USER CODE BEGIN PTD */ 35 | 36 | /* USER CODE END PTD */ 37 | 38 | /* Private define ------------------------------------------------------------*/ 39 | /* USER CODE BEGIN PD */ 40 | 41 | /* USER CODE END PD */ 42 | 43 | /* Private macro -------------------------------------------------------------*/ 44 | /* USER CODE BEGIN PM */ 45 | 46 | /* USER CODE END PM */ 47 | 48 | /* Private variables ---------------------------------------------------------*/ 49 | /* USER CODE BEGIN Variables */ 50 | 51 | /* USER CODE END Variables */ 52 | /* Definitions for DebugTask */ 53 | osThreadId_t DebugTaskHandle; 54 | const osThreadAttr_t DebugTask_attributes = { 55 | .name = "DebugTask", 56 | .priority = (osPriority_t) osPriorityNormal, 57 | .stack_size = 64 * 4 58 | }; 59 | /* Definitions for FOCTask */ 60 | osThreadId_t FOCTaskHandle; 61 | const osThreadAttr_t FOCTask_attributes = { 62 | .name = "FOCTask", 63 | .priority = (osPriority_t) osPriorityRealtime, 64 | .stack_size = 128 * 4 65 | }; 66 | /* Definitions for CommunicateTask */ 67 | osThreadId_t CommunicateTaskHandle; 68 | const osThreadAttr_t CommunicateTask_attributes = { 69 | .name = "CommunicateTask", 70 | .priority = (osPriority_t) osPriorityAboveNormal, 71 | .stack_size = 128 * 4 72 | }; 73 | /* Definitions for StartShell */ 74 | osThreadId_t StartShellHandle; 75 | const osThreadAttr_t StartShell_attributes = { 76 | .name = "StartShell", 77 | .priority = (osPriority_t) osPriorityNormal, 78 | .stack_size = 64 * 4 79 | }; 80 | 81 | /* Private function prototypes -----------------------------------------------*/ 82 | /* USER CODE BEGIN FunctionPrototypes */ 83 | 84 | /* USER CODE END FunctionPrototypes */ 85 | 86 | void StartDebugTask(void *argument); 87 | extern void StartFOCTask(void *argument); 88 | extern void StartCommunicateTask(void *argument); 89 | extern void StartStartShell(void *argument); 90 | 91 | void MX_FREERTOS_Init(void); /* (MISRA C 2004 rule 8.1) */ 92 | 93 | /** 94 | * @brief FreeRTOS initialization 95 | * @param None 96 | * @retval None 97 | */ 98 | void MX_FREERTOS_Init(void) { 99 | /* USER CODE BEGIN Init */ 100 | 101 | /* USER CODE END Init */ 102 | 103 | /* USER CODE BEGIN RTOS_MUTEX */ 104 | /* add mutexes, ... */ 105 | /* USER CODE END RTOS_MUTEX */ 106 | 107 | /* USER CODE BEGIN RTOS_SEMAPHORES */ 108 | /* add semaphores, ... */ 109 | /* USER CODE END RTOS_SEMAPHORES */ 110 | 111 | /* USER CODE BEGIN RTOS_TIMERS */ 112 | /* start timers, add new ones, ... */ 113 | /* USER CODE END RTOS_TIMERS */ 114 | 115 | /* USER CODE BEGIN RTOS_QUEUES */ 116 | /* add queues, ... */ 117 | /* USER CODE END RTOS_QUEUES */ 118 | 119 | /* Create the thread(s) */ 120 | /* creation of DebugTask */ 121 | DebugTaskHandle = osThreadNew(StartDebugTask, NULL, &DebugTask_attributes); 122 | 123 | /* creation of FOCTask */ 124 | FOCTaskHandle = osThreadNew(StartFOCTask, NULL, &FOCTask_attributes); 125 | 126 | /* creation of CommunicateTask */ 127 | CommunicateTaskHandle = osThreadNew(StartCommunicateTask, NULL, &CommunicateTask_attributes); 128 | 129 | /* creation of StartShell */ 130 | StartShellHandle = osThreadNew(StartStartShell, NULL, &StartShell_attributes); 131 | 132 | /* USER CODE BEGIN RTOS_THREADS */ 133 | /* add threads, ... */ 134 | /* USER CODE END RTOS_THREADS */ 135 | 136 | /* USER CODE BEGIN RTOS_EVENTS */ 137 | /* add events, ... */ 138 | /* USER CODE END RTOS_EVENTS */ 139 | 140 | } 141 | 142 | /* USER CODE BEGIN Header_StartDebugTask */ 143 | /** 144 | * @brief Function implementing the DebugTask thread. 145 | * @param argument: Not used 146 | * @retval None 147 | */ 148 | /* USER CODE END Header_StartDebugTask */ 149 | __weak void StartDebugTask(void *argument) 150 | { 151 | /* init code for USB_Device */ 152 | MX_USB_Device_Init(); 153 | /* USER CODE BEGIN StartDebugTask */ 154 | /* Infinite loop */ 155 | for(;;) 156 | { 157 | osDelay(1); 158 | } 159 | /* USER CODE END StartDebugTask */ 160 | } 161 | 162 | /* Private application code --------------------------------------------------*/ 163 | /* USER CODE BEGIN Application */ 164 | 165 | /* USER CODE END Application */ 166 | 167 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Inc/usbd_core.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_core.h 4 | * @author MCD Application Team 5 | * @brief Header file for usbd_core.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USBD_CORE_H 22 | #define __USBD_CORE_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_conf.h" 30 | #include "usbd_def.h" 31 | #include "usbd_ioreq.h" 32 | #include "usbd_ctlreq.h" 33 | 34 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 35 | * @{ 36 | */ 37 | 38 | /** @defgroup USBD_CORE 39 | * @brief This file is the Header file for usbd_core.c file 40 | * @{ 41 | */ 42 | 43 | 44 | /** @defgroup USBD_CORE_Exported_Defines 45 | * @{ 46 | */ 47 | #ifndef USBD_DEBUG_LEVEL 48 | #define USBD_DEBUG_LEVEL 0U 49 | #endif /* USBD_DEBUG_LEVEL */ 50 | /** 51 | * @} 52 | */ 53 | 54 | 55 | /** @defgroup USBD_CORE_Exported_TypesDefinitions 56 | * @{ 57 | */ 58 | 59 | 60 | /** 61 | * @} 62 | */ 63 | 64 | 65 | 66 | /** @defgroup USBD_CORE_Exported_Macros 67 | * @{ 68 | */ 69 | 70 | /** 71 | * @} 72 | */ 73 | 74 | /** @defgroup USBD_CORE_Exported_Variables 75 | * @{ 76 | */ 77 | #define USBD_SOF USBD_LL_SOF 78 | /** 79 | * @} 80 | */ 81 | 82 | /** @defgroup USBD_CORE_Exported_FunctionsPrototype 83 | * @{ 84 | */ 85 | USBD_StatusTypeDef USBD_Init(USBD_HandleTypeDef *pdev, USBD_DescriptorsTypeDef *pdesc, uint8_t id); 86 | USBD_StatusTypeDef USBD_DeInit(USBD_HandleTypeDef *pdev); 87 | USBD_StatusTypeDef USBD_Start(USBD_HandleTypeDef *pdev); 88 | USBD_StatusTypeDef USBD_Stop(USBD_HandleTypeDef *pdev); 89 | USBD_StatusTypeDef USBD_RegisterClass(USBD_HandleTypeDef *pdev, USBD_ClassTypeDef *pclass); 90 | 91 | USBD_StatusTypeDef USBD_RunTestMode(USBD_HandleTypeDef *pdev); 92 | USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx); 93 | USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx); 94 | 95 | USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup); 96 | USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev, uint8_t epnum, uint8_t *pdata); 97 | USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev, uint8_t epnum, uint8_t *pdata); 98 | 99 | USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev); 100 | USBD_StatusTypeDef USBD_LL_SetSpeed(USBD_HandleTypeDef *pdev, USBD_SpeedTypeDef speed); 101 | USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev); 102 | USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev); 103 | 104 | USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev); 105 | USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum); 106 | USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum); 107 | 108 | USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev); 109 | USBD_StatusTypeDef USBD_LL_DevDisconnected(USBD_HandleTypeDef *pdev); 110 | 111 | /* USBD Low Level Driver */ 112 | USBD_StatusTypeDef USBD_LL_Init(USBD_HandleTypeDef *pdev); 113 | USBD_StatusTypeDef USBD_LL_DeInit(USBD_HandleTypeDef *pdev); 114 | USBD_StatusTypeDef USBD_LL_Start(USBD_HandleTypeDef *pdev); 115 | USBD_StatusTypeDef USBD_LL_Stop(USBD_HandleTypeDef *pdev); 116 | 117 | USBD_StatusTypeDef USBD_LL_OpenEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr, 118 | uint8_t ep_type, uint16_t ep_mps); 119 | 120 | USBD_StatusTypeDef USBD_LL_CloseEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 121 | USBD_StatusTypeDef USBD_LL_FlushEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 122 | USBD_StatusTypeDef USBD_LL_StallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 123 | USBD_StatusTypeDef USBD_LL_ClearStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 124 | USBD_StatusTypeDef USBD_LL_SetUSBAddress(USBD_HandleTypeDef *pdev, uint8_t dev_addr); 125 | 126 | USBD_StatusTypeDef USBD_LL_Transmit(USBD_HandleTypeDef *pdev, uint8_t ep_addr, 127 | uint8_t *pbuf, uint32_t size); 128 | 129 | USBD_StatusTypeDef USBD_LL_PrepareReceive(USBD_HandleTypeDef *pdev, uint8_t ep_addr, 130 | uint8_t *pbuf, uint32_t size); 131 | 132 | uint8_t USBD_LL_IsStallEP(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 133 | uint32_t USBD_LL_GetRxDataSize(USBD_HandleTypeDef *pdev, uint8_t ep_addr); 134 | 135 | void USBD_LL_Delay(uint32_t Delay); 136 | 137 | /** 138 | * @} 139 | */ 140 | 141 | #ifdef __cplusplus 142 | } 143 | #endif 144 | 145 | #endif /* __USBD_CORE_H */ 146 | 147 | /** 148 | * @} 149 | */ 150 | 151 | /** 152 | * @} 153 | */ 154 | 155 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 156 | 157 | 158 | 159 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc/usbd_cdc.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_cdc.h 4 | * @author MCD Application Team 5 | * @brief header file for the usbd_cdc.c file. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USB_CDC_H 22 | #define __USB_CDC_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_ioreq.h" 30 | 31 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 32 | * @{ 33 | */ 34 | 35 | /** @defgroup usbd_cdc 36 | * @brief This file is the Header file for usbd_cdc.c 37 | * @{ 38 | */ 39 | 40 | 41 | /** @defgroup usbd_cdc_Exported_Defines 42 | * @{ 43 | */ 44 | #define CDC_IN_EP 0x81U /* EP1 for data IN */ 45 | #define CDC_OUT_EP 0x01U /* EP1 for data OUT */ 46 | #define CDC_CMD_EP 0x82U /* EP2 for CDC commands */ 47 | 48 | #ifndef CDC_HS_BINTERVAL 49 | #define CDC_HS_BINTERVAL 0x10U 50 | #endif /* CDC_HS_BINTERVAL */ 51 | 52 | #ifndef CDC_FS_BINTERVAL 53 | #define CDC_FS_BINTERVAL 0x10U 54 | #endif /* CDC_FS_BINTERVAL */ 55 | 56 | /* CDC Endpoints parameters: you can fine tune these values depending on the needed baudrates and performance. */ 57 | #define CDC_DATA_HS_MAX_PACKET_SIZE 512U /* Endpoint IN & OUT Packet size */ 58 | #define CDC_DATA_FS_MAX_PACKET_SIZE 64U /* Endpoint IN & OUT Packet size */ 59 | #define CDC_CMD_PACKET_SIZE 8U /* Control Endpoint Packet size */ 60 | 61 | #define USB_CDC_CONFIG_DESC_SIZ 67U 62 | #define CDC_DATA_HS_IN_PACKET_SIZE CDC_DATA_HS_MAX_PACKET_SIZE 63 | #define CDC_DATA_HS_OUT_PACKET_SIZE CDC_DATA_HS_MAX_PACKET_SIZE 64 | 65 | #define CDC_DATA_FS_IN_PACKET_SIZE CDC_DATA_FS_MAX_PACKET_SIZE 66 | #define CDC_DATA_FS_OUT_PACKET_SIZE CDC_DATA_FS_MAX_PACKET_SIZE 67 | 68 | #define CDC_REQ_MAX_DATA_SIZE 0x7U 69 | /*---------------------------------------------------------------------*/ 70 | /* CDC definitions */ 71 | /*---------------------------------------------------------------------*/ 72 | #define CDC_SEND_ENCAPSULATED_COMMAND 0x00U 73 | #define CDC_GET_ENCAPSULATED_RESPONSE 0x01U 74 | #define CDC_SET_COMM_FEATURE 0x02U 75 | #define CDC_GET_COMM_FEATURE 0x03U 76 | #define CDC_CLEAR_COMM_FEATURE 0x04U 77 | #define CDC_SET_LINE_CODING 0x20U 78 | #define CDC_GET_LINE_CODING 0x21U 79 | #define CDC_SET_CONTROL_LINE_STATE 0x22U 80 | #define CDC_SEND_BREAK 0x23U 81 | 82 | /** 83 | * @} 84 | */ 85 | 86 | 87 | /** @defgroup USBD_CORE_Exported_TypesDefinitions 88 | * @{ 89 | */ 90 | 91 | /** 92 | * @} 93 | */ 94 | typedef struct 95 | { 96 | uint32_t bitrate; 97 | uint8_t format; 98 | uint8_t paritytype; 99 | uint8_t datatype; 100 | } USBD_CDC_LineCodingTypeDef; 101 | 102 | typedef struct _USBD_CDC_Itf 103 | { 104 | int8_t (* Init)(void); 105 | int8_t (* DeInit)(void); 106 | int8_t (* Control)(uint8_t cmd, uint8_t *pbuf, uint16_t length); 107 | int8_t (* Receive)(uint8_t *Buf, uint32_t *Len); 108 | int8_t (* TransmitCplt)(uint8_t *Buf, uint32_t *Len, uint8_t epnum); 109 | } USBD_CDC_ItfTypeDef; 110 | 111 | 112 | typedef struct 113 | { 114 | uint32_t data[CDC_DATA_HS_MAX_PACKET_SIZE / 4U]; /* Force 32bits alignment */ 115 | uint8_t CmdOpCode; 116 | uint8_t CmdLength; 117 | uint8_t *RxBuffer; 118 | uint8_t *TxBuffer; 119 | uint32_t RxLength; 120 | uint32_t TxLength; 121 | 122 | __IO uint32_t TxState; 123 | __IO uint32_t RxState; 124 | } USBD_CDC_HandleTypeDef; 125 | 126 | 127 | 128 | /** @defgroup USBD_CORE_Exported_Macros 129 | * @{ 130 | */ 131 | 132 | /** 133 | * @} 134 | */ 135 | 136 | /** @defgroup USBD_CORE_Exported_Variables 137 | * @{ 138 | */ 139 | 140 | extern USBD_ClassTypeDef USBD_CDC; 141 | #define USBD_CDC_CLASS &USBD_CDC 142 | /** 143 | * @} 144 | */ 145 | 146 | /** @defgroup USB_CORE_Exported_Functions 147 | * @{ 148 | */ 149 | uint8_t USBD_CDC_RegisterInterface(USBD_HandleTypeDef *pdev, 150 | USBD_CDC_ItfTypeDef *fops); 151 | 152 | uint8_t USBD_CDC_SetTxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff, 153 | uint32_t length); 154 | 155 | uint8_t USBD_CDC_SetRxBuffer(USBD_HandleTypeDef *pdev, uint8_t *pbuff); 156 | uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev); 157 | uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev); 158 | /** 159 | * @} 160 | */ 161 | 162 | #ifdef __cplusplus 163 | } 164 | #endif 165 | 166 | #endif /* __USB_CDC_H */ 167 | /** 168 | * @} 169 | */ 170 | 171 | /** 172 | * @} 173 | */ 174 | 175 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 176 | -------------------------------------------------------------------------------- /Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_ioreq.c 4 | * @author MCD Application Team 5 | * @brief This file provides the IO requests APIs for control endpoints. 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Includes ------------------------------------------------------------------*/ 21 | #include "usbd_ioreq.h" 22 | 23 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 24 | * @{ 25 | */ 26 | 27 | 28 | /** @defgroup USBD_IOREQ 29 | * @brief control I/O requests module 30 | * @{ 31 | */ 32 | 33 | /** @defgroup USBD_IOREQ_Private_TypesDefinitions 34 | * @{ 35 | */ 36 | /** 37 | * @} 38 | */ 39 | 40 | 41 | /** @defgroup USBD_IOREQ_Private_Defines 42 | * @{ 43 | */ 44 | 45 | /** 46 | * @} 47 | */ 48 | 49 | 50 | /** @defgroup USBD_IOREQ_Private_Macros 51 | * @{ 52 | */ 53 | /** 54 | * @} 55 | */ 56 | 57 | 58 | /** @defgroup USBD_IOREQ_Private_Variables 59 | * @{ 60 | */ 61 | 62 | /** 63 | * @} 64 | */ 65 | 66 | 67 | /** @defgroup USBD_IOREQ_Private_FunctionPrototypes 68 | * @{ 69 | */ 70 | /** 71 | * @} 72 | */ 73 | 74 | 75 | /** @defgroup USBD_IOREQ_Private_Functions 76 | * @{ 77 | */ 78 | 79 | /** 80 | * @brief USBD_CtlSendData 81 | * send data on the ctl pipe 82 | * @param pdev: device instance 83 | * @param buff: pointer to data buffer 84 | * @param len: length of data to be sent 85 | * @retval status 86 | */ 87 | USBD_StatusTypeDef USBD_CtlSendData(USBD_HandleTypeDef *pdev, 88 | uint8_t *pbuf, uint32_t len) 89 | { 90 | /* Set EP0 State */ 91 | pdev->ep0_state = USBD_EP0_DATA_IN; 92 | pdev->ep_in[0].total_length = len; 93 | 94 | #ifdef USBD_AVOID_PACKET_SPLIT_MPS 95 | pdev->ep_in[0].rem_length = 0U; 96 | #else 97 | pdev->ep_in[0].rem_length = len; 98 | #endif 99 | 100 | /* Start the transfer */ 101 | (void)USBD_LL_Transmit(pdev, 0x00U, pbuf, len); 102 | 103 | return USBD_OK; 104 | } 105 | 106 | /** 107 | * @brief USBD_CtlContinueSendData 108 | * continue sending data on the ctl pipe 109 | * @param pdev: device instance 110 | * @param buff: pointer to data buffer 111 | * @param len: length of data to be sent 112 | * @retval status 113 | */ 114 | USBD_StatusTypeDef USBD_CtlContinueSendData(USBD_HandleTypeDef *pdev, 115 | uint8_t *pbuf, uint32_t len) 116 | { 117 | /* Start the next transfer */ 118 | (void)USBD_LL_Transmit(pdev, 0x00U, pbuf, len); 119 | 120 | return USBD_OK; 121 | } 122 | 123 | /** 124 | * @brief USBD_CtlPrepareRx 125 | * receive data on the ctl pipe 126 | * @param pdev: device instance 127 | * @param buff: pointer to data buffer 128 | * @param len: length of data to be received 129 | * @retval status 130 | */ 131 | USBD_StatusTypeDef USBD_CtlPrepareRx(USBD_HandleTypeDef *pdev, 132 | uint8_t *pbuf, uint32_t len) 133 | { 134 | /* Set EP0 State */ 135 | pdev->ep0_state = USBD_EP0_DATA_OUT; 136 | pdev->ep_out[0].total_length = len; 137 | 138 | #ifdef USBD_AVOID_PACKET_SPLIT_MPS 139 | pdev->ep_out[0].rem_length = 0U; 140 | #else 141 | pdev->ep_out[0].rem_length = len; 142 | #endif 143 | 144 | /* Start the transfer */ 145 | (void)USBD_LL_PrepareReceive(pdev, 0U, pbuf, len); 146 | 147 | return USBD_OK; 148 | } 149 | 150 | /** 151 | * @brief USBD_CtlContinueRx 152 | * continue receive data on the ctl pipe 153 | * @param pdev: device instance 154 | * @param buff: pointer to data buffer 155 | * @param len: length of data to be received 156 | * @retval status 157 | */ 158 | USBD_StatusTypeDef USBD_CtlContinueRx(USBD_HandleTypeDef *pdev, 159 | uint8_t *pbuf, uint32_t len) 160 | { 161 | (void)USBD_LL_PrepareReceive(pdev, 0U, pbuf, len); 162 | 163 | return USBD_OK; 164 | } 165 | 166 | /** 167 | * @brief USBD_CtlSendStatus 168 | * send zero lzngth packet on the ctl pipe 169 | * @param pdev: device instance 170 | * @retval status 171 | */ 172 | USBD_StatusTypeDef USBD_CtlSendStatus(USBD_HandleTypeDef *pdev) 173 | { 174 | /* Set EP0 State */ 175 | pdev->ep0_state = USBD_EP0_STATUS_IN; 176 | 177 | /* Start the transfer */ 178 | (void)USBD_LL_Transmit(pdev, 0x00U, NULL, 0U); 179 | 180 | return USBD_OK; 181 | } 182 | 183 | /** 184 | * @brief USBD_CtlReceiveStatus 185 | * receive zero lzngth packet on the ctl pipe 186 | * @param pdev: device instance 187 | * @retval status 188 | */ 189 | USBD_StatusTypeDef USBD_CtlReceiveStatus(USBD_HandleTypeDef *pdev) 190 | { 191 | /* Set EP0 State */ 192 | pdev->ep0_state = USBD_EP0_STATUS_OUT; 193 | 194 | /* Start the transfer */ 195 | (void)USBD_LL_PrepareReceive(pdev, 0U, NULL, 0U); 196 | 197 | return USBD_OK; 198 | } 199 | 200 | /** 201 | * @brief USBD_GetRxCount 202 | * returns the received data length 203 | * @param pdev: device instance 204 | * @param ep_addr: endpoint address 205 | * @retval Rx Data blength 206 | */ 207 | uint32_t USBD_GetRxCount(USBD_HandleTypeDef *pdev, uint8_t ep_addr) 208 | { 209 | return USBD_LL_GetRxDataSize(pdev, ep_addr); 210 | } 211 | 212 | /** 213 | * @} 214 | */ 215 | 216 | 217 | /** 218 | * @} 219 | */ 220 | 221 | 222 | /** 223 | * @} 224 | */ 225 | 226 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 227 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/projdefs.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 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 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/stack_macros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 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 | -------------------------------------------------------------------------------- /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) 2024 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 "fdcan.h" 24 | #include "spi.h" 25 | #include "tim.h" 26 | #include "usb_device.h" 27 | #include "gpio.h" 28 | 29 | /* Private includes ----------------------------------------------------------*/ 30 | /* USER CODE BEGIN Includes */ 31 | 32 | /* USER CODE END Includes */ 33 | 34 | /* Private typedef -----------------------------------------------------------*/ 35 | /* USER CODE BEGIN PTD */ 36 | 37 | /* USER CODE END PTD */ 38 | 39 | /* Private define ------------------------------------------------------------*/ 40 | /* USER CODE BEGIN PD */ 41 | 42 | /* USER CODE END PD */ 43 | 44 | /* Private macro -------------------------------------------------------------*/ 45 | /* USER CODE BEGIN PM */ 46 | 47 | /* USER CODE END PM */ 48 | 49 | /* Private variables ---------------------------------------------------------*/ 50 | 51 | /* USER CODE BEGIN PV */ 52 | 53 | /* USER CODE END PV */ 54 | 55 | /* Private function prototypes -----------------------------------------------*/ 56 | void SystemClock_Config(void); 57 | void MX_FREERTOS_Init(void); 58 | /* USER CODE BEGIN PFP */ 59 | 60 | /* USER CODE END PFP */ 61 | 62 | /* Private user code ---------------------------------------------------------*/ 63 | /* USER CODE BEGIN 0 */ 64 | 65 | /* USER CODE END 0 */ 66 | 67 | /** 68 | * @brief The application entry point. 69 | * @retval int 70 | */ 71 | int main(void) 72 | { 73 | 74 | /* USER CODE BEGIN 1 */ 75 | 76 | /* USER CODE END 1 */ 77 | 78 | /* MCU Configuration--------------------------------------------------------*/ 79 | 80 | /* Reset of all peripherals, Initializes the Flash interface and the Systick. */ 81 | HAL_Init(); 82 | 83 | /* USER CODE BEGIN Init */ 84 | 85 | /* USER CODE END Init */ 86 | 87 | /* Configure the system clock */ 88 | SystemClock_Config(); 89 | 90 | /* USER CODE BEGIN SysInit */ 91 | 92 | /* USER CODE END SysInit */ 93 | 94 | /* Initialize all configured peripherals */ 95 | MX_GPIO_Init(); 96 | MX_ADC1_Init(); 97 | MX_TIM6_Init(); 98 | MX_ADC2_Init(); 99 | MX_FDCAN1_Init(); 100 | MX_SPI1_Init(); 101 | MX_TIM1_Init(); 102 | /* USER CODE BEGIN 2 */ 103 | 104 | /* USER CODE END 2 */ 105 | 106 | /* Init scheduler */ 107 | osKernelInitialize(); 108 | 109 | /* Call init function for freertos objects (in cmsis_os2.c) */ 110 | MX_FREERTOS_Init(); 111 | 112 | /* Start scheduler */ 113 | osKernelStart(); 114 | 115 | /* We should never get here as control is now taken by the scheduler */ 116 | 117 | /* Infinite loop */ 118 | /* USER CODE BEGIN WHILE */ 119 | while (1) { 120 | /* USER CODE END WHILE */ 121 | 122 | /* USER CODE BEGIN 3 */ 123 | } 124 | /* USER CODE END 3 */ 125 | } 126 | 127 | /** 128 | * @brief System Clock Configuration 129 | * @retval None 130 | */ 131 | void SystemClock_Config(void) 132 | { 133 | RCC_OscInitTypeDef RCC_OscInitStruct = {0}; 134 | RCC_ClkInitTypeDef RCC_ClkInitStruct = {0}; 135 | 136 | /** Configure the main internal regulator output voltage 137 | */ 138 | HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1_BOOST); 139 | 140 | /** Initializes the RCC Oscillators according to the specified parameters 141 | * in the RCC_OscInitTypeDef structure. 142 | */ 143 | RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI|RCC_OSCILLATORTYPE_HSI48; 144 | RCC_OscInitStruct.HSIState = RCC_HSI_ON; 145 | RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; 146 | RCC_OscInitStruct.HSI48State = RCC_HSI48_ON; 147 | RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; 148 | RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; 149 | RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV4; 150 | RCC_OscInitStruct.PLL.PLLN = 85; 151 | RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; 152 | RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV4; 153 | RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2; 154 | if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) 155 | { 156 | Error_Handler(); 157 | } 158 | 159 | /** Initializes the CPU, AHB and APB buses clocks 160 | */ 161 | RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK 162 | |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; 163 | RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; 164 | RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; 165 | RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1; 166 | RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; 167 | 168 | if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK) 169 | { 170 | Error_Handler(); 171 | } 172 | } 173 | 174 | /* USER CODE BEGIN 4 */ 175 | 176 | /* USER CODE END 4 */ 177 | 178 | /** 179 | * @brief This function is executed in case of error occurrence. 180 | * @retval None 181 | */ 182 | void Error_Handler(void) 183 | { 184 | /* USER CODE BEGIN Error_Handler_Debug */ 185 | /* User can add his own implementation to report the HAL error return state */ 186 | __disable_irq(); 187 | while (1) { 188 | } 189 | /* USER CODE END Error_Handler_Debug */ 190 | } 191 | 192 | #ifdef USE_FULL_ASSERT 193 | /** 194 | * @brief Reports the name of the source file and the source line number 195 | * where the assert_param error has occurred. 196 | * @param file: pointer to the source file name 197 | * @param line: assert_param error line source number 198 | * @retval None 199 | */ 200 | void assert_failed(uint8_t *file, uint32_t line) 201 | { 202 | /* USER CODE BEGIN 6 */ 203 | /* User can add his own implementation to report the file name and line number, 204 | ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */ 205 | /* USER CODE END 6 */ 206 | } 207 | #endif /* USE_FULL_ASSERT */ 208 | -------------------------------------------------------------------------------- /Middlewares/Third_Party/FreeRTOS/Source/include/StackMacros.h: -------------------------------------------------------------------------------- 1 | /* 2 | * FreeRTOS Kernel V10.3.1 3 | * Copyright (C) 2020 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 | -------------------------------------------------------------------------------- /UserLib/LetterShell/Inc/shell_cfg.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file shell_cfg.h 3 | * @author Letter (nevermindzzt@gmail.com) 4 | * @brief shell config 5 | * @version 3.0.0 6 | * @date 2019-12-31 7 | * 8 | * @copyright (c) 2019 Letter 9 | * 10 | */ 11 | 12 | #ifndef __SHELL_CFG_H__ 13 | #define __SHELL_CFG_H__ 14 | 15 | #ifdef SHELL_CFG_USER 16 | #include SHELL_CFG_USER 17 | #endif 18 | 19 | #ifndef SHELL_TASK_WHILE 20 | /** 21 | * @brief 是否使用默认shell任务while循环 22 | * 使能此宏,则`shellTask()`函数会一直循环读取输入,一般使用操作系统建立shell 23 | * 任务时使能此宏,关闭此宏的情况下,一般适用于无操作系统,在主循环中调用`shellTask()` 24 | */ 25 | #define SHELL_TASK_WHILE 1 26 | #endif /** SHELL_TASK_WHILE */ 27 | 28 | #ifndef SHELL_USING_CMD_EXPORT 29 | /** 30 | * @brief 是否使用命令导出方式 31 | * 使能此宏后,可以使用`SHELL_EXPORT_CMD()`等导出命令 32 | * 定义shell命令,关闭此宏的情况下,需要使用命令表的方式 33 | */ 34 | #define SHELL_USING_CMD_EXPORT 1 35 | #endif /** SHELL_USING_CMD_EXPORT */ 36 | 37 | #ifndef SHELL_USING_COMPANION 38 | /** 39 | * @brief 是否使用shell伴生对象 40 | * 一些扩展的组件(文件系统支持,日志工具等)需要使用伴生对象 41 | */ 42 | #define SHELL_USING_COMPANION 0 43 | #endif /** SHELL_USING_COMPANION */ 44 | 45 | #ifndef SHELL_SUPPORT_END_LINE 46 | /** 47 | * @brief 支持shell尾行模式 48 | */ 49 | #define SHELL_SUPPORT_END_LINE 0 50 | #endif /** SHELL_SUPPORT_END_LINE */ 51 | 52 | #ifndef SHELL_HELP_LIST_USER 53 | /** 54 | * @brief 是否在输出命令列表中列出用户 55 | */ 56 | #define SHELL_HELP_LIST_USER 0 57 | #endif /** SHELL_HELP_LIST_USER */ 58 | 59 | #ifndef SHELL_HELP_LIST_VAR 60 | /** 61 | * @brief 是否在输出命令列表中列出变量 62 | */ 63 | #define SHELL_HELP_LIST_VAR 0 64 | #endif /** SHELL_HELP_LIST_VAR */ 65 | 66 | #ifndef SHELL_HELP_LIST_KEY 67 | /** 68 | * @brief 是否在输出命令列表中列出按键 69 | */ 70 | #define SHELL_HELP_LIST_KEY 0 71 | #endif /** SHELL_HELP_LIST_KEY */ 72 | 73 | #ifndef SHELL_HELP_SHOW_PERMISSION 74 | /** 75 | * @brief 是否在输出命令列表中展示命令权限 76 | */ 77 | #define SHELL_HELP_SHOW_PERMISSION 1 78 | #endif /** SHELL_HELP_SHOW_PERMISSION */ 79 | 80 | #ifndef SHELL_ENTER_LF 81 | /** 82 | * @brief 使用LF作为命令行回车触发 83 | * 可以和SHELL_ENTER_CR同时开启 84 | */ 85 | #define SHELL_ENTER_LF 1 86 | #endif /** SHELL_ENTER_LF */ 87 | 88 | #ifndef SHELL_ENTER_CR 89 | /** 90 | * @brief 使用CR作为命令行回车触发 91 | * 可以和SHELL_ENTER_LF同时开启 92 | */ 93 | #define SHELL_ENTER_CR 1 94 | #endif /** SHELL_ENTER_CR */ 95 | 96 | #ifndef SHELL_ENTER_CRLF 97 | /** 98 | * @brief 使用CRLF作为命令行回车触发 99 | * 不可以和SHELL_ENTER_LF或SHELL_ENTER_CR同时开启 100 | */ 101 | #define SHELL_ENTER_CRLF 0 102 | #endif /** SHELL_ENTER_CRLF */ 103 | 104 | #ifndef SHELL_EXEC_UNDEF_FUNC 105 | /** 106 | * @brief 使用执行未导出函数的功能 107 | * 启用后,可以通过`exec [addr] [args]`直接执行对应地址的函数 108 | * @attention 如果地址错误,可能会直接引起程序崩溃 109 | */ 110 | #define SHELL_EXEC_UNDEF_FUNC 0 111 | #endif /** SHELL_EXEC_UNDEF_FUNC */ 112 | 113 | #ifndef SHELL_PARAMETER_MAX_NUMBER 114 | /** 115 | * @brief shell命令参数最大数量 116 | * 包含命令名在内,超过16个参数并且使用了参数自动转换的情况下,需要修改源码 117 | */ 118 | #define SHELL_PARAMETER_MAX_NUMBER 8 119 | #endif /** SHELL_PARAMETER_MAX_NUMBER */ 120 | 121 | #ifndef SHELL_HISTORY_MAX_NUMBER 122 | /** 123 | * @brief 历史命令记录数量 124 | */ 125 | #define SHELL_HISTORY_MAX_NUMBER 5 126 | #endif /** SHELL_HISTORY_MAX_NUMBER */ 127 | 128 | #ifndef SHELL_DOUBLE_CLICK_TIME 129 | /** 130 | * @brief 双击间隔(ms) 131 | * 使能宏`SHELL_LONG_HELP`后此宏生效,定义双击tab补全help的时间间隔 132 | */ 133 | #define SHELL_DOUBLE_CLICK_TIME 200 134 | #endif /** SHELL_DOUBLE_CLICK_TIME */ 135 | 136 | #ifndef SHELL_QUICK_HELP 137 | /** 138 | * @brief 快速帮助 139 | * 作用于双击tab的场景,当使能此宏时,双击tab不会对命令进行help补全,而是直接显示对应命令的帮助信息 140 | */ 141 | #define SHELL_QUICK_HELP 1 142 | #endif /** SHELL_QUICK_HELP */ 143 | 144 | #ifndef SHELL_KEEP_RETURN_VALUE 145 | /** 146 | * @brief 保存命令返回值 147 | * 开启后会默认定义一个`RETVAL`变量,会保存上一次命令执行的返回值,可以在随后的命令中进行调用 148 | * 如果命令的`SHELL_CMD_DISABLE_RETURN`标志被设置,则该命令不会更新`RETVAL` 149 | */ 150 | #define SHELL_KEEP_RETURN_VALUE 0 151 | #endif /** SHELL_KEEP_RETURN_VALUE */ 152 | 153 | #ifndef SHELL_MAX_NUMBER 154 | /** 155 | * @brief 管理的最大shell数量 156 | */ 157 | #define SHELL_MAX_NUMBER 5 158 | #endif /** SHELL_MAX_NUMBER */ 159 | 160 | #ifndef SHELL_PRINT_BUFFER 161 | /** 162 | * @brief shell格式化输出的缓冲大小 163 | * 为0时不使用shell格式化输出 164 | */ 165 | #define SHELL_PRINT_BUFFER 128 166 | #endif /** SHELL_PRINT_BUFFER */ 167 | 168 | #ifndef SHELL_SCAN_BUFFER 169 | /** 170 | * @brief shell格式化输入的缓冲大小 171 | * 为0时不使用shell格式化输入 172 | * @note shell格式化输入会阻塞shellTask, 仅适用于在有操作系统的情况下使用 173 | */ 174 | #define SHELL_SCAN_BUFFER 0 175 | #endif /** SHELL_SCAN_BUFFER */ 176 | 177 | #ifndef SHELL_GET_TICK 178 | /** 179 | * @brief 获取系统时间(ms) 180 | * 定义此宏为获取系统Tick,如`HAL_GetTick()` 181 | * @note 此宏不定义时无法使用双击tab补全命令help,无法使用shell超时锁定 182 | */ 183 | #define SHELL_GET_TICK() 0 184 | #endif /** SHELL_GET_TICK */ 185 | 186 | #ifndef SHELL_USING_LOCK 187 | /** 188 | * @brief 使用锁 189 | * @note 使用shell锁时,需要对加锁和解锁进行实现 190 | */ 191 | #define SHELL_USING_LOCK 0 192 | #endif /** SHELL_USING_LOCK */ 193 | 194 | #ifndef SHELL_MALLOC 195 | /** 196 | * @brief shell内存分配 197 | * shell本身不需要此接口,若使用shell伴生对象,需要进行定义 198 | */ 199 | #define SHELL_MALLOC(size) 0 200 | #endif /** SHELL_MALLOC */ 201 | 202 | #ifndef SHELL_FREE 203 | /** 204 | * @brief shell内存释放 205 | * shell本身不需要此接口,若使用shell伴生对象,需要进行定义 206 | */ 207 | #define SHELL_FREE(obj) 0 208 | #endif /** SHELL_FREE */ 209 | 210 | #ifndef SHELL_SHOW_INFO 211 | /** 212 | * @brief 是否显示shell信息 213 | */ 214 | #define SHELL_SHOW_INFO 1 215 | #endif /** SHELL_SHOW_INFO */ 216 | 217 | #ifndef SHELL_CLS_WHEN_LOGIN 218 | /** 219 | * @brief 是否在登录后清除命令行 220 | */ 221 | #define SHELL_CLS_WHEN_LOGIN 1 222 | #endif /** SHELL_CLS_WHEN_LOGIN */ 223 | 224 | #ifndef SHELL_DEFAULT_USER 225 | /** 226 | * @brief shell默认用户 227 | */ 228 | #define SHELL_DEFAULT_USER "letter" 229 | #endif /** SHELL_DEFAULT_USER */ 230 | 231 | #ifndef SHELL_DEFAULT_USER_PASSWORD 232 | /** 233 | * @brief shell默认用户密码 234 | * 若默认用户不需要密码,设为"" 235 | */ 236 | #define SHELL_DEFAULT_USER_PASSWORD "" 237 | #endif /** SHELL_DEFAULT_USER_PASSWORD */ 238 | 239 | #ifndef SHELL_LOCK_TIMEOUT 240 | /** 241 | * @brief shell自动锁定超时 242 | * shell当前用户密码有效的时候生效,超时后会自动重新锁定shell 243 | * 设置为0时关闭自动锁定功能,时间单位为`SHELL_GET_TICK()`单位 244 | * @note 使用超时锁定必须保证`SHELL_GET_TICK()`有效 245 | */ 246 | #define SHELL_LOCK_TIMEOUT 0 * 60 * 1000 247 | #endif /** SHELL_LOCK_TIMEOUT */ 248 | 249 | #ifndef SHELL_USING_FUNC_SIGNATURE 250 | /** 251 | * @brief 使用函数签名 252 | * 使能后,可以在声明命令时,指定函数的签名,shell 会根据函数签名进行参数转换, 253 | * 而不是自动判断参数的类型,如果参数和函数签名不匹配,会停止执行命令 254 | */ 255 | #define SHELL_USING_FUNC_SIGNATURE 0 256 | #endif /** SHELL_USING_FUNC_SIGNATURE */ 257 | 258 | #ifndef SHELL_SUPPORT_ARRAY_PARAM 259 | /** 260 | * @brief 支持数组参数 261 | * 使能后,可以在命令中使用数组参数,如`cmd [1,2,3]` 262 | * 需要使能 `SHELL_USING_FUNC_SIGNATURE` 宏,并且配置 `SHELL_MALLOC`, `SHELL_FREE` 263 | */ 264 | #define SHELL_SUPPORT_ARRAY_PARAM 0 265 | #endif /** SHELL_SUPPORT_ARRAY_PARAM */ 266 | 267 | #endif 268 | -------------------------------------------------------------------------------- /cmake/stm32cubemx/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.22) 2 | # Enable CMake support for ASM and C languages 3 | enable_language(C ASM) 4 | # STM32CubeMX generated symbols (macros) 5 | set(MX_Defines_Syms 6 | USE_HAL_DRIVER 7 | STM32G431xx 8 | $<$:DEBUG> 9 | ) 10 | 11 | # STM32CubeMX generated include paths 12 | set(MX_Include_Dirs 13 | ${CMAKE_SOURCE_DIR}/Core/Inc 14 | ${CMAKE_SOURCE_DIR}/USB_Device/App 15 | ${CMAKE_SOURCE_DIR}/USB_Device/Target 16 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Inc 17 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Inc/Legacy 18 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/include 19 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2 20 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F 21 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Core/Inc 22 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Inc 23 | ${CMAKE_SOURCE_DIR}/Drivers/CMSIS/Device/ST/STM32G4xx/Include 24 | ${CMAKE_SOURCE_DIR}/Drivers/CMSIS/Include 25 | ) 26 | 27 | # STM32CubeMX generated application sources 28 | set(MX_Application_Src 29 | ${CMAKE_SOURCE_DIR}/USB_Device/App/usb_device.c 30 | ${CMAKE_SOURCE_DIR}/USB_Device/App/usbd_desc.c 31 | ${CMAKE_SOURCE_DIR}/USB_Device/App/usbd_cdc_if.c 32 | ${CMAKE_SOURCE_DIR}/USB_Device/Target/usbd_conf.c 33 | ${CMAKE_SOURCE_DIR}/Core/Src/main.c 34 | ${CMAKE_SOURCE_DIR}/Core/Src/gpio.c 35 | ${CMAKE_SOURCE_DIR}/Core/Src/app_freertos.c 36 | ${CMAKE_SOURCE_DIR}/Core/Src/adc.c 37 | ${CMAKE_SOURCE_DIR}/Core/Src/fdcan.c 38 | ${CMAKE_SOURCE_DIR}/Core/Src/spi.c 39 | ${CMAKE_SOURCE_DIR}/Core/Src/tim.c 40 | ${CMAKE_SOURCE_DIR}/Core/Src/stm32g4xx_it.c 41 | ${CMAKE_SOURCE_DIR}/Core/Src/stm32g4xx_hal_msp.c 42 | ${CMAKE_SOURCE_DIR}/Core/Src/sysmem.c 43 | ${CMAKE_SOURCE_DIR}/Core/Src/syscalls.c 44 | ${CMAKE_SOURCE_DIR}/startup_stm32g431xx.s 45 | ) 46 | 47 | # STM32 HAL/LL Drivers 48 | set(STM32_Drivers_Src 49 | ${CMAKE_SOURCE_DIR}/Core/Src/system_stm32g4xx.c 50 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pcd.c 51 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pcd_ex.c 52 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_ll_usb.c 53 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal.c 54 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc.c 55 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_rcc_ex.c 56 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash.c 57 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ex.c 58 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_flash_ramfunc.c 59 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_gpio.c 60 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_exti.c 61 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma.c 62 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_dma_ex.c 63 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr.c 64 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_pwr_ex.c 65 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_cortex.c 66 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_adc.c 67 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_adc_ex.c 68 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_ll_adc.c 69 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_fdcan.c 70 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_spi.c 71 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_spi_ex.c 72 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim.c 73 | ${CMAKE_SOURCE_DIR}/Drivers/STM32G4xx_HAL_Driver/Src/stm32g4xx_hal_tim_ex.c 74 | ) 75 | 76 | # Drivers Midllewares 77 | 78 | 79 | set(USB_Device_Library_Src 80 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_core.c 81 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ctlreq.c 82 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Core/Src/usbd_ioreq.c 83 | ${CMAKE_SOURCE_DIR}/Middlewares/ST/STM32_USB_Device_Library/Class/CDC/Src/usbd_cdc.c 84 | ) 85 | set(FreeRTOS_Src 86 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/croutine.c 87 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/event_groups.c 88 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/list.c 89 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/queue.c 90 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/stream_buffer.c 91 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/tasks.c 92 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/timers.c 93 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c 94 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/portable/MemMang/heap_4.c 95 | ${CMAKE_SOURCE_DIR}/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c 96 | ) 97 | 98 | # Link directories setup 99 | set(MX_LINK_DIRS 100 | 101 | ) 102 | # Project static libraries 103 | set(MX_LINK_LIBS 104 | STM32_Drivers 105 | USB_Device_Library FreeRTOS 106 | ) 107 | # Interface library for includes and symbols 108 | add_library(stm32cubemx INTERFACE) 109 | target_include_directories(stm32cubemx INTERFACE ${MX_Include_Dirs}) 110 | target_compile_definitions(stm32cubemx INTERFACE ${MX_Defines_Syms}) 111 | 112 | # Create STM32_Drivers static library 113 | add_library(STM32_Drivers OBJECT) 114 | target_sources(STM32_Drivers PRIVATE ${STM32_Drivers_Src}) 115 | target_link_libraries(STM32_Drivers PUBLIC stm32cubemx) 116 | 117 | 118 | # Create USB_Device_Library static library 119 | add_library(USB_Device_Library OBJECT) 120 | target_sources(USB_Device_Library PRIVATE ${USB_Device_Library_Src}) 121 | target_link_libraries(USB_Device_Library PUBLIC stm32cubemx) 122 | 123 | # Create FreeRTOS static library 124 | add_library(FreeRTOS OBJECT) 125 | target_sources(FreeRTOS PRIVATE ${FreeRTOS_Src}) 126 | target_link_libraries(FreeRTOS PUBLIC stm32cubemx) 127 | 128 | # Add STM32CubeMX generated application sources to the project 129 | target_sources(${CMAKE_PROJECT_NAME} PRIVATE ${MX_Application_Src}) 130 | 131 | # Link directories setup 132 | target_link_directories(${CMAKE_PROJECT_NAME} PRIVATE ${MX_LINK_DIRS}) 133 | 134 | # Add libraries to the project 135 | target_link_libraries(${CMAKE_PROJECT_NAME} ${MX_LINK_LIBS}) 136 | 137 | # Add the map file to the list of files to be removed with 'clean' target 138 | set_target_properties(${CMAKE_PROJECT_NAME} PROPERTIES ADDITIONAL_CLEAN_FILES ${CMAKE_PROJECT_NAME}.map) 139 | 140 | # Validate that STM32CubeMX code is compatible with C standard 141 | if((CMAKE_C_STANDARD EQUAL 90) OR (CMAKE_C_STANDARD EQUAL 99)) 142 | message(ERROR "Generated code requires C11 or higher") 143 | endif() 144 | -------------------------------------------------------------------------------- /UserLib/LetterShell/Inc/shell_cpp.h: -------------------------------------------------------------------------------- 1 | /** 2 | * @file shell_cpp.h 3 | * @author Letter (nevermindzzt@gmail.com) 4 | * @brief shell cpp support 5 | * @version 1.0.0 6 | * @date 2021-01-09 7 | * 8 | * @copyright (c) 2021 Letter 9 | * 10 | */ 11 | #ifndef __SHELL_CPP_H__ 12 | #define __SHELL_CPP_H__ 13 | 14 | #ifdef __cplusplus 15 | extern "C" { 16 | 17 | #include "shell.h" 18 | 19 | /** 20 | * @brief shell command cpp 支持 cmd 定义 21 | */ 22 | typedef struct shell_command_cpp_cmd 23 | { 24 | int attr; /**< 属性 */ 25 | const char *name; /**< 命令名 */ 26 | int (*function)(); /**< 命令执行函数 */ 27 | const char *desc; /**< 命令描述 */ 28 | #if SHELL_USING_FUNC_SIGNATURE == 1 29 | const char *signature; /**< 函数签名 */ 30 | #endif 31 | } ShellCommandCppCmd; 32 | 33 | /** 34 | * @brief shell command cpp 支持 var 定义 35 | */ 36 | typedef struct shell_command_cpp_var 37 | { 38 | int attr; /**< 属性 */ 39 | const char *name; /**< 变量名 */ 40 | void *value; /**< 变量值 */ 41 | const char *desc; /**< 变量描述 */ 42 | #if SHELL_USING_FUNC_SIGNATURE == 1 43 | void *unused; /**< 未使用成员,需要保持和 ShellCommandCppCmd 大小一致 */ 44 | #endif 45 | } ShellCommandCppVar; 46 | 47 | /** 48 | * @brief shell command cpp 支持 user 定义 49 | */ 50 | typedef struct shell_command_cpp_user 51 | { 52 | int attr; /**< 属性 */ 53 | const char *name; /**< 用户名 */ 54 | const char *password; /**< 用户密码 */ 55 | const char *desc; /**< 用户描述 */ 56 | #if SHELL_USING_FUNC_SIGNATURE == 1 57 | void *unused; /**< 未使用成员,需要保持和 ShellCommandCppCmd 大小一致 */ 58 | #endif 59 | } ShellCommandCppUser; 60 | 61 | /** 62 | * @brief shell command cpp 支持 key 定义 63 | */ 64 | typedef struct shell_command_cpp_key 65 | { 66 | int attr; /**< 属性 */ 67 | int value; /**< 按键键值 */ 68 | void (*function)(Shell *); /**< 按键执行函数 */ 69 | const char *desc; /**< 按键描述 */ 70 | #if SHELL_USING_FUNC_SIGNATURE == 1 71 | void *unused; /**< 未使用成员,需要保持和 ShellCommandCppCmd 大小一致 */ 72 | #endif 73 | } ShellCommandCppKey; 74 | 75 | #if SHELL_USING_FUNC_SIGNATURE == 1 76 | typedef struct shell_command_cpp_param_parser 77 | { 78 | int attr; /**< 属性 */ 79 | const char *type; /**< 参数类型 */ 80 | int (*parser)(char *, void **);; /**< 解析函数 */ 81 | int (*cleaner)(void *); /**< 清理函数 */ 82 | void *unsed; /**< 未使用成员,需要保持和 ShellCommandCppCmd 大小一致 */ 83 | } ShellCommandCppParamParser; 84 | #endif 85 | 86 | #if SHELL_USING_CMD_EXPORT == 1 87 | 88 | #undef SHELL_EXPORT_CMD 89 | /** 90 | * @brief shell 命令定义 91 | * 92 | * @param _attr 命令属性 93 | * @param _name 命令名 94 | * @param _func 命令函数 95 | * @param _desc 命令描述 96 | * @param ... 其他参数 97 | */ 98 | #define SHELL_EXPORT_CMD(_attr, _name, _func, _desc, ...) \ 99 | const char shellCmd##_name[] = #_name; \ 100 | const char shellDesc##_name[] = #_desc; \ 101 | extern "C" SHELL_USED const ShellCommandCppCmd \ 102 | shellCommand##_name SHELL_SECTION("shellCommand") = \ 103 | { \ 104 | _attr, \ 105 | shellCmd##_name, \ 106 | (int (*)())_func, \ 107 | shellDesc##_name, \ 108 | ##__VA_ARGS__ \ 109 | } 110 | 111 | #undef SHELL_EXPORT_VAR 112 | /** 113 | * @brief shell 变量定义 114 | * 115 | * @param _attr 变量属性 116 | * @param _name 变量名 117 | * @param _value 变量值 118 | * @param _desc 变量描述 119 | */ 120 | #define SHELL_EXPORT_VAR(_attr, _name, _value, _desc) \ 121 | const char shellCmd##_name[] = #_name; \ 122 | const char shellDesc##_name[] = #_desc; \ 123 | extern "C" SHELL_USED const ShellCommandCppVar \ 124 | shellVar##_name SHELL_SECTION("shellCommand") = \ 125 | { \ 126 | _attr, \ 127 | shellCmd##_name, \ 128 | (void *)_value, \ 129 | shellDesc##_name \ 130 | } 131 | 132 | #undef SHELL_EXPORT_USER 133 | /** 134 | * @brief shell 用户定义 135 | * 136 | * @param _attr 用户属性 137 | * @param _name 用户名 138 | * @param _password 用户密码 139 | * @param _desc 用户描述 140 | */ 141 | #define SHELL_EXPORT_USER(_attr, _name, _password, _desc) \ 142 | const char shellCmd##_name[] = #_name; \ 143 | const char shellPassword##_name[] = #_password; \ 144 | const char shellDesc##_name[] = #_desc; \ 145 | extern "C" SHELL_USED const ShellCommandCppUser \ 146 | shellUser##_name SHELL_SECTION("shellCommand") = \ 147 | { \ 148 | _attr|SHELL_CMD_TYPE(SHELL_TYPE_USER), \ 149 | shellCmd##_name, \ 150 | shellPassword##_name, \ 151 | shellDesc##_name \ 152 | } 153 | 154 | #undef SHELL_EXPORT_KEY 155 | /** 156 | * @brief shell 按键定义 157 | * 158 | * @param _attr 按键属性 159 | * @param _value 按键键值 160 | * @param _func 按键函数 161 | * @param _desc 按键描述 162 | */ 163 | #define SHELL_EXPORT_KEY(_attr, _value, _func, _desc) \ 164 | const char shellDesc##_value[] = #_desc; \ 165 | extern "C" SHELL_USED const ShellCommandCppKey \ 166 | shellKey##_value SHELL_SECTION("shellCommand") = \ 167 | { \ 168 | _attr|SHELL_CMD_TYPE(SHELL_TYPE_KEY), \ 169 | _value, \ 170 | (void (*)(Shell *))_func, \ 171 | shellDesc##_value \ 172 | } 173 | 174 | #if SHELL_USING_FUNC_SIGNATURE == 1 175 | #undef SHELL_EXPORT_PARAM_PARSER 176 | /** 177 | * @brief shell 参数解析器定义 178 | * 179 | * @param _attr 参数解析器属性 180 | * @param _type 参数解析器类型 181 | * @param _parser 参数解析器函数 182 | * @param _cleaner 参数清理函数 183 | */ 184 | #define SHELL_EXPORT_PARAM_PARSER(_attr, _type, _parser, _cleaner) \ 185 | const char shellDesc##_parser[] = #_type; \ 186 | extern "C" SHELL_USED const ShellCommandCppParamParser \ 187 | shellCommand##_parser SHELL_SECTION("shellCommand") = \ 188 | { \ 189 | _attr|SHELL_CMD_TYPE(SHELL_TYPE_PARAM_PARSER), \ 190 | shellDesc##_parser, \ 191 | (int (*)(char *, void **))_parser, \ 192 | (int (*)(void *))_cleaner \ 193 | } 194 | #endif 195 | #endif /** SHELL_USING_CMD_EXPORT == 1 */ 196 | 197 | } 198 | #endif /**< defined __cplusplus */ 199 | 200 | #endif /**< __SHELL_CPP_H__ */ 201 | --------------------------------------------------------------------------------