diff --git a/.vscode/launch.json b/.vscode/launch.json index b7051ea..56720ef 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -1,24 +1,25 @@ { "version": "0.2.0", "configurations": [ - { + { // 使用dap-link(如无线调试器时的参考配置) "name": "Debug-dap", "cwd": "${workspaceRoot}", - "executable": "${workspaceRoot}\\build\\basic_framework.elf", + "executable": "${workspaceRoot}\\build\\basic_framework.elf", // 要下载到调试器的文件 "request": "launch", "type": "cortex-debug", - "device":"STM32F407IG", //使用J-link GDB Server时必须;其他GBD Server时可选(有可能帮助自动选择SVD文件)。支持的设备见 https://www.segger.com/downloads/supported-devices.php - "svdFile": ".\\STM32F407.svd", //svd文件,有这个文件才能查看寄存器的值,每个单片机都不同。可以在以下地址找到 https://github.com/posborne/cmsis-svd - "servertype": "openocd", //使用的GDB Server - "configFiles":[ - ".\\openocd.cfg", + "device": "STM32F407IG", //使用J-link GDB Server时必须;其他GBD Server时可选(有可能帮助自动选择SVD文件)。支持的设备见 https://www.segger.com/downloads/supported-devices.php + "svdFile": ".\\STM32F407.svd", //svd文件,有这个文件才能查看寄存器的值,每个单片机都不同。可以在以下地址找到 https://github.com/posborne/cmsis-svd + // 该项目的根目录已经提供了C型开发板使用的外设svd文件 + "servertype": "openocd", //使用的GDB Server + "configFiles": [ + ".\\openocd.cfg", // 配置文件已经在根目录提供,若要修改以此类推 ], - // path to your gcc-arm-none-eabi/bin + // path to your gcc-arm-none-eabi/bin,如果在cortex-debug的设置中写入了全局路径,这里不需要再写 "armToolchainPath": "D:\\gcc-arm-none-eabi\\bin", - // path to your gcc-arm-none-eabi/arm-none-eabi-gdb.exe - "gdbPath": "D:\\gcc-arm-none-eabi\\bin\\arm-none-eabi-gdb.exe" + // path to your gcc-arm-none-eabi/arm-none-eabi-gdb.exe,如果在cortex-debug的设置中写入了全局路径,这里不需要再写 + "gdbPath": "D:\\gcc-arm-none-eabi\\bin\\arm-none-eabi-gdb.exe" }, - { + { // 使用j-link时的参考配置 "name": "Debug-jlink", "cwd": "${workspaceFolder}", "executable": "${workspaceRoot}\\build\\basic_framework.elf", @@ -29,8 +30,10 @@ "showDevDebugOutput": "none", "servertype": "jlink", "interface": "swd", + //如果在cortex-debug的设置中写入了全局路径,这里不需要再写 "armToolchainPath": "D:\\gcc-arm-none-eabi\\bin", - "gdbPath": "D:\\gcc-arm-none-eabi\\bin\\arm-none-eabi-gdb.exe" + //如果在cortex-debug的设置中写入了全局路径,这里不需要再写 + "gdbPath": "D:\\gcc-arm-none-eabi\\bin\\arm-none-eabi-gdb.exe" } ] } \ No newline at end of file diff --git a/Makefile b/Makefile index d0213b7..6b76ffb 100644 --- a/Makefile +++ b/Makefile @@ -105,6 +105,7 @@ bsp/bsp_can.c \ bsp/bsp_buzzer.c \ bsp/bsp_usart.c \ bsp/bsp_log.c \ +bsp/bsp_init.c \ \ \ modules/algorithm/controller.c \ modules/algorithm/kalman_filter.c \ @@ -117,6 +118,7 @@ modules/master_machine/master_process.c \ modules/motor/dji_motor.c \ modules/motor/HT04.c \ modules/motor/LK9025.c \ +modules/mode/step_motor.c \ modules/motor/motor_task.c \ modules/referee/referee.c \ modules/referee/referee_UI.c \ @@ -125,7 +127,8 @@ modules/remote/remote_control.c \ modules/super_cap/super_cap.c \ modules/master_machine/seasky_protocol.c \ modules/algorithm/crc8.c \ -modules/algorithm/crc16.c +modules/algorithm/crc16.c \ +modules/can_comm/can_comm.c # ASM sources diff --git a/README.md b/README.md index cb2fafb..57259e9 100644 --- a/README.md +++ b/README.md @@ -100,10 +100,11 @@ Module层主要存放的是类型定义和实例指针数组,在该层没有 ## 文件树 +板级支持包的每个组件,每个moduel,每个app都有对应的说明文档. ```shell ROOT:. │ .gitignore # git版本管理忽略文件 -│ .mxproject # CubeMX项目文件 +│ .mxproject # CubeMX项目文件 │ basic_framework.ioc # CubeMX初始化配置文件 │ Makefile # 编译管理文件,为make命令的目标 │ openocd.cfg # 用于OpenOCD调试使用的配置文件 @@ -111,39 +112,50 @@ ROOT:. │ startup_stm32f407xx.s # F407汇编启动文件 │ STM32F407.svd # F407外设地址映射文件,用于调试 │ STM32F407IGHx_FLASH.ld # F407IGH(C板使用的MCU)的文件目标FLASH地址,用于烧录和调试 -│ +│ VSCode+Ozone使用方法.md # 开发环境配置 +| ├─.vscode │ launch.json # 用于VSCode插件CORTEX-DEBUG调试的配置文件 │ ├─application # 应用层,包括底盘控制,云台控制和发射控制 │ chassis.c │ chassis.h +│ chassis.md │ gimbal.c │ gimbal.h +│ gimbal.md │ shoot.c │ shoot.h +│ shoot.md │ ├─bsp # 板级支持包,提供对硬件的封装,将接口暴露给module层 +│ bsp.md │ bsp_buzzer.c │ bsp_buzzer.h │ bsp_can.c │ bsp_can.h +│ bsp_can.md │ bsp_dwt.c │ bsp_dwt.h +│ bsp_init.c +│ bsp_init.h │ bsp_led.c │ bsp_led.h │ bsp_log.c │ bsp_log.h +│ bsp_log.md │ bsp_temperature.c │ bsp_temperature.h │ bsp_usart.c │ bsp_usart.h +│ bsp_usart.md │ struct_typedef.h │ ├─HAL_N_Middlewares # HAL库对寄存器操作的封装,以及FreeRTOS等中间件 | └─modules # 模块层,使用BSP提供的接口构建对应的功能模块,将模块实例提供给应用层 ├─algorithm # 算法 + │ algorithm.md │ controller.c # 控制器 │ controller.h │ crc16.c # 循环冗余校验 @@ -159,6 +171,11 @@ ROOT:. │ user_lib.c # 多个模块都会使用到的函数 │ user_lib.h │ + ├─can_comm # 双板CAN通信组件 + │ can_comm.c + │ can_comm.h + │ can_comm.md + | ├─imu # 考虑到使用SPI的设备较少,这里没有对SPI提供bsp支持,直接于此实现 │ BMI088driver.c │ BMI088driver.h @@ -173,10 +190,12 @@ ROOT:. │ led_task.h │ ├─master_machine # 和上位机(视觉PC)通信的模块 - │ master_process.c + │ master_process.c │ master_process.h - │ seasky_protocol.c # 视觉通信协议 + │ master_process.md + │ seasky_protocol.c │ seasky_protocol.h + │ 湖南大学RoboMaster电控组通信协议.md │ ├─motor # 电机模块 │ dji_motor.c # DJI智能电机 @@ -193,7 +212,8 @@ ROOT:. │ referee.c # 接收裁判系统信息 │ referee.h │ referee_UI.c # UI绘制(发送) - │ + │ referee_communication.c # 多机通信 + | ├─remote # 遥控器模块 │ remote_control.c │ remote_control.h diff --git a/VSCode+Ozone使用方法.md b/VSCode+Ozone使用方法.md index 92ee851..bfcb4f6 100644 --- a/VSCode+Ozone使用方法.md +++ b/VSCode+Ozone使用方法.md @@ -1,2 +1,199 @@ -# VSCode+Ozone使用方法 +# VSCode+Ozone开发STM32的方法 + +
neozng1@hnu.edu.cn
+ +[TOC] + +## 前言 + +了解过嵌入式开发的你一定接触过Keil,这款20世纪风格UI的IDE伴随很多人度过了学习单片机的岁月。然而由于其缺少代码补全、高亮和静态检查的支持,以及为人诟病的一系列逆天的设置、极慢的编译速度(特别是在开发HAL库时),很多开发者开始转向其他IDE。 + +IAR、CubeIDE等都是广为使用的“其他”IDE,但是他们也有各自的缺点,不能让笔者满意。作为IDE界的艺术家,JetBrains推出的Clion也在相当程度上完善了对嵌入式开发的支持。不过,在体验过多款IDE后,还是**VSCode**这款高度定制化的编辑器最让人满意。 + +而Ozone则是SEGGER(做jilnk的)推出的调试应用,支持变量实时更新,变量曲线可视化,SEGGER RTT日志,DBG虚拟串口等功能,大大扩展了调试的功能。很多人习惯使用串口进行可视化调试,如vofa,串口调试助手等。然而通过这些方式进行调试,都是对内核有**侵入性**的,会占有内核资源并且导致定时器的时间错乱。由于DBG有单独连接到FLASH和CPU寄存器的高速总线(类似于DMA),可以在不影响程序正常运行的情况下以极高的频率直接获取变量值。 + +下面,将从工具链介绍、环境配置以及调试工作流三个方面介绍以VSCode为编辑器,Ozone为调试接口的开发环境。 + +开发的大致流程为: + +~~~mermaid +graph LR +CubeMX进行初始化 --> VSCode编写代/进行编译/简单调试 --> Ozone变量可视化调试+log +~~~ + +## 前置知识 + +1. 计算机速成课:[Crash Course Computer Science](https://www.bilibili.com/video/av21376839/?vd_source=ddae2b7332590050afe28928f52f0bda) + +2. 从零到一打造一台计算机: + + [编程前你最好了解的基本硬件和计算机基础知识(模拟电路)](https://www.bilibili.com/video/BV1774114798/?spm_id_from=333.788.recommend_more_video.11&vd_source=ddae2b7332590050afe28928f52f0bda) + + [编程前你最好了解的基本硬件和计算机基础知识(数字电路)](https://www.bilibili.com/video/BV1Hi4y1t7zY/?spm_id_from=333.788.recommend_more_video.0) + + [从0到1设计一台计算机](https://www.bilibili.com/video/BV1wi4y157D3/?spm_id_from=333.788.recommend_more_video.0&vd_source=ddae2b7332590050afe28928f52f0bda) + +3. C语言基础:[程序设计入门——C语言](https://www.icourse163.org/course/ZJU-199001?from=searchPage&outVendor=zw_mooc_pcssjg_) + +***务必学完以上课程再开始本教程的学习。*** + +## 预备知识 + +1. 软件安装(队伍NAS和资料硬盘内提供了所有必要的依赖,安装包和插件) +2. C语言从源代码到.bin和.hex等机器代码的编译和链接过程 +3. C语言的内存模型 +4. C语言标准,动态链接库和静态编译的区别,一些编译器的常用选项 +5. STM32F4系列的DBG外设工作原理 + +### 编译全过程 + +C语言代码由固定的词汇(关键字)按照固定的格式(语法)组织起来,简单直观,程序员容易识别和理解,但是CPU只能识别二进制形式的指令,并且这些指令是和硬件相关的(感兴趣的同学可以搜索**指令集**相关内容)。这就需要一个工具,将C语言代码转换成CPU能够识别的二进制指令,对于我们的x86平台windows下的程序就是.exe后缀的文件;对于单片机,一般来说是.bin或.hex等格式的文件(调试文件包括axf和elf)。 + +能够完成这个转化过程的工具是一个特殊的软件,叫做**编译器(Compiler)**。常见的编译器包括开源的GNU GCC,windows下微软开发的visual C++,以及apple主导的llvm/clang。编译器能够识别代码中的关键字、表达式以及各种特定的格式,并将他们转换成特定的符号,也就是**汇编语言**(再次注意汇编语言是平台特定的),这个过程称为**编译(Compile)**。 + +对于单个.c文件,从C语言开始到单片机可识别的.bin文件,一般要经历以下几步: + +![img](https://pic3.zhimg.com/80/v2-2797ea99d0d38eb9996993bb0ad77ab2_720w.webp) + +首先是编译**预处理**Preprocessing,这一步会展开宏并删除注释,将多余的空格去除。预处理之后会生成.i文件。 + +然后,开始**编译**Compilation的工作。编译器会将源代码进行语法分析、词法分析、语义分析等,根据编译设置进行性能优化,然后生成汇编代码.s文件。汇编代码仍然是以助记符的形式记录的文本,比如将某个地址的数据加载到CPU寄存器等,还需要进一步翻译成二进制代码。 + +下一步就是进行**汇编**Assemble,编译器会根据汇编助记符和机器代码的查找表将所有符号进行替换,生成.o .obj等文件。但请注意,这些文件并不能直接使用(烧录),我们在编写代码的时候,都会包含一些**库**,因此编译结果应当有多个.o文件。我们还需要一种方法将这些目标文件缝合在一起,使得在遇到函数调用的时候,程序可以正确地跳转到对应的地方执行。 + +最后一步就由链接器Linker(也称LD)完成,称为**链接**Linking。比如你编写了一个motor.c文件和.h文件,并在main.c中包含了motor.h,使用了后者提供的`MotorControl()`函数。那么,链接器会根据编译器生成.obj文件时留下的函数入口地址,将main.o里的调用映射到生成的motor.o中。链接完成后,就生成了单片机可以识别的可执行文件,通过支持的串口或下载器烧录,便可以运行。 + +> 另外,上图可以看到左侧的**静态库**,包括`.lib .a`,比如我们在STM32中使用的DSP运算库就是这种文件。他在本质上和.o文件相同,只要你在你编写的源文件中包含了这些库的头文件,链接器就可以根据映射关系找到头文件中声明的函数在库文件的地址。(直接提供库而不是.c文件,就可以防止源代码泄露,因此一些不开源的程序会提供函数调用的头文件和接口具体实现的库;你也可以编写自己的库,感兴趣自行搜索) + +链接之后,实际上还要进行不同代码片段的重组、地址重映射,详细的内容请参看:[C/C++语言编译链接过程](https://zhuanlan.zhihu.com/p/88255667),这篇教程还提供了以GCC为例的代码编译示例。 + +### C语言内存模型 + +image-20221112160213066 + +以上是C语言常见的内存模型,即C语言的代码块以及运行时使用的内存(包括函数、变量等)的组织方式。 + +> 有些平台的图与此相反,栈在最下面(内存低地址),其他区域都倒置,不影响我们理解 + +**代码段**即我们编写的代码,也就是前面说的编译和链接之后最终生成的可执行文件占据的空间。一些常量,包括字符串和使用`const`关键字修饰的变量被放在常量存储区。`static`修饰的静态变量(包括函数静态变量和文件静态变量)以及全局变量放在常量区上面一点的全局区(也称静态区)。 + +然后就是最重要的**堆**和**栈**。在一个代码块内定义的变量会被放在栈区,一旦离开作用域(出了它被定义的`{}`的区域),就会立刻被销毁。在调用函数或进入一个用户自定义的`{}`块,都会在栈上开辟一块新的空间,空间的大小和内存分配由操作系统或C库自动管理。**一般来说,直接通过变量访问栈内存,速度最快**(对于单片机)。而堆则是存储程序员自行分配的变量的地方,即使用`malloc(),realloc() ,new`等方法获取的空间,都被分配在这里。 + +> 在CubeMX初始化的时候,Project mananger标签页下有一个Linker Setting的选项,这里是设置最小堆内存和栈内存的地方。如果你的程序里写了大规模的数组,或使用`malloc()`等分配了大量的空间,可能出现栈溢出或堆挤占栈空间的情况。需要根据MCU的资源大小,设置合适的stack size和heap size。 + +### C language标准和编译器 + +不同的C语言标准(一般以年份作代号)支持的语法特性和关键字不同,拥有的功能也不同。一般来说语言标准都是向前兼容的,在更新之后仍然会保存前代的基本功能支持(legacy support)。不过,为了程序能够正常运行,我们还需要一些硬件或平台支持的组件。比如`malloc()`这个函数,在linux平台和windows平台上的具体实现就相去甚远,跟单片机更是差了不止一点。前两者一般和对应的操作系统有关,后者在裸机上则是直接通过硬件或ST公司提供的硬件抽象层代码实现。 + +然而,不同编译器提供的代码实现也不尽相同,比如使用clang和gcc这两种c语言编译器,他们对于一些标准库(也称C库,包括stdio,stdlib,string等在内的实现)的函数的实现就不太一样。再如`__packed`是arm-cc提供的一个字节不对齐关键字,在一些其他编译器中就不支持这种实现。 + +以前大家常用的KEIL使用的是ARM提供的arm-cc工具链(非常蛋疼,甚至不支持uint8_t=0b00001111这种二进制定义法),而该教程选用的是开源的**Arm GNU Toolchain**。在非目标机且和目标机平台不同的平台上进行开发被成为**跨平台开发**,进行的编译也被成为**交叉编译**(在一个平台上生成另一个平台上的 可执行代码)。 + +> 工具链包含了编译器,链接器以及调试器等开发常用组件。我们使用的Arm GNU toolchain中,编译器是`arm-none-eabi-gcc.exe`,链接器是`arm-none-eabi-ld.exe`,调试器则是`arm-none-eabi-gdb.exe`。通过跨平台调试器和j-link/st-link/dap-link,我们就可以在自己的电脑上对异构平台(即单片机)的运行进行调试了。 + +### Debug外设工作原理 + +![image-20221112145717063](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112145717063.png) + +DBG支持模块(红框标注部分,也可以看作一个外设)通过一条专用的AHB-AP总线和调试接口相连(Jtag或swd),并且有与**数据**和**外设**总线直接相连的桥接器。它还同时连接了中断嵌套管理器(因此同样可以捕获中断并进行debug)和ITM、DWT、FPB这些调试支持模块。因此DBG可以直接获取内存或片上外设内的数据而不需要占用CPU的资源,并将这些数据通过专用外设总线发送给调试器,进而在上位机中读取。 + +FPB是flash patch breakpoint闪存指令断点的缩写,用于提供代码断点插入的支持,当CPU的指令寄存器读取到某一条指令时,FPB会监测到它的动作,并通知TPIU暂停CPU进行现场保护。 + +DWT是data watch trace数据观察与追踪单元的缩写,用于比较debug变量的大小,并追踪变量值的变化。当你设定了比较断点规则(当某个数据大于/小于某个值时暂停程序)或将变量加入watch进行查看,DWT就会开始工作。DWT还提供了一个额外的计时器,即所有可见的TIM资源之外的另一个硬件计时器(因为调试其他硬件定时器的计时由于时钟变化可能定时不准,而DWT定时器是始终正常运行的)。它用于给自身和其他调试器模块产生的信息打上时间戳。我们的bsp中也封装了dwt计时器,你可以使用它来计时。 + +ITM是instrument trace macrocell指令追踪宏单元的缩写,它用于提供非阻塞式的日志发送支持(相当于大家常用的串口调试),SEGGER RTT就可以利用这个模块,向上位机发送日志和信息。 + +以上三个模块都需要通过TPIU(trace port interface unit)和外部调试器(j-link等)进行连接,TPIU会将三个模块发来的数据进行封装并通过DWT记录时间,发送给上位机。 + +## 环境配置 + +- 安装STM32CubeMX,并安装F4支持包和DSP库支持包- + +- 安装VSCode,并安装C/C++,Cortex-Debug,Cortex-Debug: Device Support Pack - STM32F4,Better C++ Syntax,IntelliCode,Makfile Tools,C/C++ Snippets插件 + + ![image-20221112172157533](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172157533.png) + + ![image-20221112172208749](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172208749.png) + + ![image-20221112172221756](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172221756.png) + + ![image-20221112172239386](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172239386.png) + + ![image-20221112172254809](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172254809.png) + +- 安装MinGW,等待界面如下: + + ![image-20221112172051589](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172051589.png) + + 安装好后,打开MinGW后将所有的支持包勾选,然后安装: + + ![image-20221112172348408](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172348408.png) + + ![image-20221112172420037](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172420037.png) + + 安装完以后,将MinGW的bin文件夹添加到环境变量中的path下,按下菜单键搜索**编辑系统环境变量**打开之后: + + ![image-20221112172716320](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172716320.png) + + 验证安装: + + 打开命令行(win+R,cmd,回车),输入`gcc -v`,如果没有报错,并输出了一堆路径和参数说明安装成功。 + +- 配置gcc-arm-none-eabi环境变量 + + 同上,将工具链的bin添加到PATH: + + ![image-20221112172858593](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112172858593.png) + +
安装路径可能不一样,这里要使用你自己的路径而不是直接抄
+ + 验证安装: + + 打开命令行,输入`arm-none-eabi-gcc -v`,如果没有报错,并输出了一堆路径和参数说明安装成功。 + +> 添加到环境变量PATH的意思是,当一些程序需要某些依赖或者要打开某些程序时,系统会自动前往PATH下寻找对应项。**一般需要重启使环境变量生效。** + +- **将OpenOCD解压到一个文件夹里**,稍后需要在VSCode中设置这个路径。 + +- CubeMX生成代码的时候工具链选择makefile + + ![image-20221112173534670](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112173534670.png) + + 生成的目录结构如下: + + ![image-20221112174211802](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112174211802.png) + + Makefile就是我们要使用的构建规则文件。 + +## VSCode编译和调试配置 + +### 编译 + +用VSCode打开创建的项目文件夹,**Makefile Tools插件会询问你是否帮助配置intellisense,选择是。** + + + + + + + + + + + +### 简单调试 + +> 在VSCode中调试不能像Keil一样查看变量动态变化,但是支持以外的所有操作,如查看外设和反汇编代码,设置断点触发方式等。 + +用于调试的配置参考这篇博客:[Cortex-debug 调试器使用介绍](https://blog.csdn.net/qq_40833810/article/details/106713462) + +你需要配置**arm gnu工具链的路径**,**OpenOCD的路径**(使得GDB调试器可以找到OpenOCD并调用它,从而连接硬件调试器如j-link等),该工作区(文件夹)的**launch.json文件**(用于启动vscode的调试任务)。 + +如果教程看不懂,请看`.vscode`下的`launch.json`,照葫芦画瓢。 + +根目录下已经提供了C板所需的.svd和使用无线调试器时所用的openocd.cfg配置文件。 + +然后选择run and debug标签页,在选项中选择你配置好的选项,开始调试。 + +![image-20221112180103750](C:\Users\Neo\AppData\Roaming\Typora\typora-user-images\image-20221112180103750.png) diff --git a/application/chassis.md b/application/chassis.md new file mode 100644 index 0000000..e69de29 diff --git a/application/gimbal.md b/application/gimbal.md new file mode 100644 index 0000000..e69de29 diff --git a/application/shoot.md b/application/shoot.md new file mode 100644 index 0000000..e69de29 diff --git a/bsp/bsp.md b/bsp/bsp.md new file mode 100644 index 0000000..e69de29 diff --git a/bsp/bsp_init.c b/bsp/bsp_init.c new file mode 100644 index 0000000..e69de29 diff --git a/bsp/bsp_init.h b/bsp/bsp_init.h new file mode 100644 index 0000000..e69de29 diff --git a/modules/algorithm/algorithm.md b/modules/algorithm/algorithm.md new file mode 100644 index 0000000..c2b4c6d --- /dev/null +++ b/modules/algorithm/algorithm.md @@ -0,0 +1,32 @@ +# algorithms + +

neozng1@hnu.edu.cn

+ +> TODO: +> +> 1. 实现麦轮和全向轮的速度解算 +> 2. 实现LQR +> 3. 实现一些通用的滤波器,如指数平均,窗平均,低通等 +> 4. 实现系统辨识 + +## 总览和使用 + +module层的algorithm提供了一些供其他模块以及app的应用层使用的算法,包括: + +1. PID控制器`controller.h` +2. crc8 crc16循环冗余校验 +3. 卡尔曼滤波器`kalman_filter.h`,可以通过用户自定义函数配置为扩展卡尔曼滤波 +4. `LQR.h`,线性二次型调节器 +5. `QuaterninoEKF.h`,用于`ins_task`的四元数姿态解算和扩展卡尔曼滤波融合 +6. `user_lib.h`,一些通用的函数,包括限幅、数据类型转换、角度弧度转换、快速符号判断以及优化开方等功能。多个模块都会使用的、不好区分的函数可以放置于此 + +## 代码结构 + +.c 为算法的实现,.h为算法对外接口的头文件 + + + +在编写应用的时候,你基本不会使用这里的函数,或是修改其实现。 + +若发现bug或需要增加功能,联系组长讨论。 + diff --git a/modules/algorithm/user_lib.c b/modules/algorithm/user_lib.c index f1754b7..a2d0a92 100644 --- a/modules/algorithm/user_lib.c +++ b/modules/algorithm/user_lib.c @@ -2,7 +2,8 @@ ****************************************************************************** * @file user_lib.c * @author Wang Hongxi - * @version V1.0.0 + * @author modified by neozng + * @version 0.2 beta * @date 2021/2/18 * @brief ****************************************************************************** @@ -24,7 +25,7 @@ uint8_t GlobalDebugMode = 7; -//快速开方 +// 快速开方 float Sqrt(float x) { float y; @@ -51,29 +52,7 @@ float Sqrt(float x) return y; } -/** - * @brief 斜波函数计算,根据输入的值进行叠加, 输入单位为 /s 即一秒后增加输入的值 - * @author RM - * @param[in] 斜波函数结构体 - * @param[in] 输入值 - * @retval 返回空 - */ -float ramp_calc(ramp_function_source_t *ramp_source_type, float input) -{ - ramp_source_type->input = input; - ramp_source_type->out += ramp_source_type->input * ramp_source_type->frame_period; - if (ramp_source_type->out > ramp_source_type->max_value) - { - ramp_source_type->out = ramp_source_type->max_value; - } - else if (ramp_source_type->out < ramp_source_type->min_value) - { - ramp_source_type->out = ramp_source_type->min_value; - } - return ramp_source_type->out; -} - -//绝对值限制 +// 绝对值限制 float abs_limit(float num, float Limit) { if (num > Limit) @@ -87,7 +66,7 @@ float abs_limit(float num, float Limit) return num; } -//判断符号位 +// 判断符号位 float sign(float value) { if (value >= 0.0f) @@ -100,7 +79,7 @@ float sign(float value) } } -//浮点死区 +// 浮点死区 float float_deadband(float Value, float minValue, float maxValue) { if (Value < maxValue && Value > minValue) @@ -120,7 +99,7 @@ int16_t int16_deadline(int16_t Value, int16_t minValue, int16_t maxValue) return Value; } -//限幅函数 +// 限幅函数 float float_constrain(float Value, float minValue, float maxValue) { if (Value < minValue) @@ -131,7 +110,7 @@ float float_constrain(float Value, float minValue, float maxValue) return Value; } -//限幅函数 +// 限幅函数 int16_t int16_constrain(int16_t Value, int16_t minValue, int16_t maxValue) { if (Value < minValue) @@ -142,7 +121,7 @@ int16_t int16_constrain(int16_t Value, int16_t minValue, int16_t maxValue) return Value; } -//循环限幅函数 +// 循环限幅函数 float loop_float_constrain(float Input, float minValue, float maxValue) { if (maxValue < minValue) @@ -169,9 +148,9 @@ float loop_float_constrain(float Input, float minValue, float maxValue) return Input; } -//弧度格式化为-PI~PI +// 弧度格式化为-PI~PI -//角度格式化为-180~180 +// 角度格式化为-180~180 float theta_format(float Ang) { return loop_float_constrain(Ang, -180.0f, 180.0f); diff --git a/modules/algorithm/user_lib.h b/modules/algorithm/user_lib.h index 56f7ca8..d223225 100644 --- a/modules/algorithm/user_lib.h +++ b/modules/algorithm/user_lib.h @@ -87,39 +87,9 @@ extern uint8_t GlobalDebugMode; #define VAL_MIN(a, b) ((a) < (b) ? (a) : (b)) #define VAL_MAX(a, b) ((a) > (b) ? (a) : (b)) -typedef struct -{ - float input; //�������� - float out; //������� - float min_value; //�޷���Сֵ - float max_value; //�޷����ֵ - float frame_period; //ʱ���� -} ramp_function_source_t; - -typedef struct -{ - uint16_t Order; - uint32_t Count; - - float *x; - float *y; - - float k; - float b; - - float StandardDeviation; - - float t[4]; -} Ordinary_Least_Squares_t; //���ٿ��� float Sqrt(float x); - -//б��������ʼ�� -void ramp_init(ramp_function_source_t *ramp_source_type, float frame_period, float max, float min); -//б���������� -float ramp_calc(ramp_function_source_t *ramp_source_type, float input); - //�������� float abs_limit(float num, float Limit); //�жϷ���λ diff --git a/modules/can_comm/can_comm.c b/modules/can_comm/can_comm.c new file mode 100644 index 0000000..e69de29 diff --git a/modules/can_comm/can_comm.h b/modules/can_comm/can_comm.h new file mode 100644 index 0000000..e69de29 diff --git a/modules/can_comm/can_comm.md b/modules/can_comm/can_comm.md new file mode 100644 index 0000000..b9bea44 --- /dev/null +++ b/modules/can_comm/can_comm.md @@ -0,0 +1,3 @@ +can_comm + +双板CAN通信 \ No newline at end of file diff --git a/modules/led_light/led.md b/modules/led_light/led.md new file mode 100644 index 0000000..c99ee17 --- /dev/null +++ b/modules/led_light/led.md @@ -0,0 +1,6 @@ +# led_task +

neozng1@hnu.edu.cn

+ +> TODO: +> 1. 预计添加不同错误标志,将错误类型和灯的闪烁频率或颜色等对应起来,方便调试 + diff --git a/modules/master_machine/master_process.c b/modules/master_machine/master_process.c index 4a9f933..db1bef8 100644 --- a/modules/master_machine/master_process.c +++ b/modules/master_machine/master_process.c @@ -12,11 +12,14 @@ /* use usart1 as vision communication*/ static Vision_Recv_s recv_data; +// @todo:由于后续需要进行IMU-Cam的硬件触发采集控制,因此可能需要将发送设置为定时任务,或由IMU采集完成产生的中断唤醒的任务, +// 使得时间戳对齐. 因此,在send_data中设定其他的标志位数据,让ins_task填充姿态值. +// static Vision_Send_s send_data; static usart_instance vision_usart_instance; /** * @brief 接收解包回调函数,将在bsp_usart.c中被usart rx callback调用 - * @todo 1.提高可读性,将get_protocol_info的第四个参数增加一个float buffer + * @todo 1.提高可读性,将get_protocol_info的第四个参数增加一个float类型buffer * 2.添加标志位解码 */ static void DecodeVision() @@ -38,8 +41,10 @@ Vision_Recv_s* VisionInit(UART_HandleTypeDef *handle) /** * @brief 发送函数 - * @todo 1.提高可读性,将get_protocol_info的第四个参数增加一个float buffer + * @todo 1.提高可读性,将get_protocol_send_data的第6个参数增加一个float buffer * 2.添加标志位解码 + * 3.由于后续需要进行IMU-Cam的硬件触发采集控制,因此可能需要将发送设置为定时任务 + * 或由IMU采集完成产生的中断唤醒的任务,使得时间戳对齐. * * @param send 待发送数据 */ @@ -53,3 +58,9 @@ void VisionSend(Vision_Send_s *send) get_protocol_send_data(0x02, flag_register, &send->yaw, 3, send_buff, &tx_len); USARTSend(&vision_usart_instance, send_buff, tx_len); } + + +Vision_Recv_s* VisionGetcmd() +{ + return &recv_data; +} \ No newline at end of file diff --git a/modules/master_machine/master_process.h b/modules/master_machine/master_process.h index 4e79552..8338a40 100644 --- a/modules/master_machine/master_process.h +++ b/modules/master_machine/master_process.h @@ -22,4 +22,11 @@ Vision_Recv_s *VisionInit(UART_HandleTypeDef *handle); */ void VisionSend(Vision_Send_s *send); +/** + * @brief 返回所需的上位机数据 + * + * @return Vision_Recv_s* 数据结构体指针 + */ +Vision_Recv_s* VisionGetcmd(); + #endif // !MASTER_PROCESS_H \ No newline at end of file diff --git a/modules/master_machine/seasky_protocol.h b/modules/master_machine/seasky_protocol.h index bc3369a..2bdc180 100644 --- a/modules/master_machine/seasky_protocol.h +++ b/modules/master_machine/seasky_protocol.h @@ -6,7 +6,7 @@ #define PROTOCOL_CMD_ID 0XA5 -#define OFFSET_BYTE 8 //出数据段外,其他部分所占字节数 +#define OFFSET_BYTE 8 // 出数据段外,其他部分所占字节数 typedef enum { @@ -77,7 +77,7 @@ typedef struct float pitch; float roll; - // uint32_t time_stamp; + // uint32_t time_stamp; // @todo 用于和相机的时间戳对齐 } Vision_Send_s; typedef struct @@ -86,23 +86,23 @@ typedef struct { uint8_t sof; uint16_t data_length; - uint8_t crc_check; //帧头CRC校验 - } header; //数据帧头 - uint16_t cmd_id; //数据ID - uint16_t frame_tail; //帧尾CRC校验 + uint8_t crc_check; // 帧头CRC校验 + } header; // 数据帧头 + uint16_t cmd_id; // 数据ID + uint16_t frame_tail; // 帧尾CRC校验 } protocol_rm_struct; /*更新发送数据帧,并计算发送数据帧长度*/ -void get_protocol_send_data(uint16_t send_id, //信号id +void get_protocol_send_data(uint16_t send_id, // 信号id uint16_t flags_register, // 16位寄存器 - float *tx_data, //待发送的float数据 + float *tx_data, // 待发送的float数据 uint8_t float_length, // float的数据长度 - uint8_t *tx_buf, //待发送的数据帧 - uint16_t *tx_buf_len); //待发送的数据帧长度 + uint8_t *tx_buf, // 待发送的数据帧 + uint16_t *tx_buf_len); // 待发送的数据帧长度 /*接收数据处理*/ -uint16_t get_protocol_info(uint8_t *rx_buf, //接收到的原始数据 - uint16_t *flags_register, //接收数据的16位寄存器地址 - float *rx_data); //接收的float数据存储地址 +uint16_t get_protocol_info(uint8_t *rx_buf, // 接收到的原始数据 + uint16_t *flags_register, // 接收数据的16位寄存器地址 + float *rx_data); // 接收的float数据存储地址 #endif diff --git a/modules/motor/dji_motor.h b/modules/motor/dji_motor.h index cf4b3e8..ddd515a 100644 --- a/modules/motor/dji_motor.h +++ b/modules/motor/dji_motor.h @@ -2,13 +2,11 @@ * @file dji_motor.h * @author neozng * @brief DJI智能电机头文件 - * @version 0.1 + * @version 0.2 * @date 2022-11-01 * * @todo 1. 给不同的电机设置不同的低通滤波器惯性系数而不是统一使用宏 - 2. 当前电机初始化函数`DJIMotorInit()`稍显凌乱, - 应设置一个`dji_motor_init_config_s`结构体用于电机初始化,使得风格统一,提高可读性 - 3. 为M2006和M3508增加开环的零位校准函数 + 2. 为M2006和M3508增加开环的零位校准函数 * @copyright Copyright (c) 2022 HNU YueLu EC all rights reserved * @@ -28,13 +26,13 @@ /* DJI电机CAN反馈信息*/ typedef struct { - uint16_t ecd; + uint16_t ecd; // 0-8192 uint16_t last_ecd; - int16_t speed_rpm; - int16_t given_current; + int16_t speed_rpm; // rounds per minute + int16_t given_current; // 实际电流 uint8_t temperate; - int16_t total_round; - int32_t total_angle; + int16_t total_round; // 总圈数,注意方向 + int32_t total_angle; // 总角度,注意方向 } dji_motor_measure; /** @@ -66,19 +64,18 @@ typedef struct /** * @brief 调用此函数注册一个DJI智能电机,需要传递较多的初始化参数,请在application初始化的时候调用此函数 * 推荐传参时像标准库一样构造initStructure然后传入此函数. - * recommend: type xxxinitStructure = { - * .member1=xx, - * .member2=xx, - * ....}; + * recommend: type xxxinitStructure = {.member1=xx, + * .member2=xx, + * ....}; * 请注意不要在一条总线上挂载过多的电机(超过6个),若一定要这么做,请降低每个电机的反馈频率(设为500Hz), * 并减小DJIMotorControl()任务的运行频率. * * @attention M3508和M2006的反馈报文都是0x200+id,而GM6020的反馈是0x204+id,请注意前两者和后者的id不要冲突. * 如果产生冲突,在初始化电机的时候会进入IDcrash_Handler(),可以通过debug来判断是否出现冲突. - * + * * @param config 电机初始化结构体,包含了电机控制设置,电机PID参数设置,电机类型以及电机挂载的CAN设置 - * - * @return dji_motor_instance* + * + * @return dji_motor_instance* */ dji_motor_instance *DJIMotorInit(Motor_Init_Config_s config); diff --git a/modules/motor/dji_motor.md b/modules/motor/dji_motor.md index a931ce8..97c5a46 100644 --- a/modules/motor/dji_motor.md +++ b/modules/motor/dji_motor.md @@ -5,8 +5,7 @@ > TODO: > > 1. 给不同的电机设置不同的低通滤波器惯性系数而不是统一使用宏 -> 2. 当前电机初始化函数`DJIMotorInit()`稍显凌乱,应设置一个`dji_motor_init_config_s`结构体用于电机初始化,使得风格统一,提高可读性 -> 3. 为M2006和M3508增加开环的零位校准函数 +> 2. 为M2006和M3508增加开环的零位校准函数 diff --git a/modules/motor/step_motor.c b/modules/motor/step_motor.c new file mode 100644 index 0000000..e69de29 diff --git a/modules/motor/step_motor.h b/modules/motor/step_motor.h new file mode 100644 index 0000000..e69de29 diff --git a/modules/referee/referee.md b/modules/referee/referee.md new file mode 100644 index 0000000..e69de29 diff --git a/modules/remote/remote.md b/modules/remote/remote.md new file mode 100644 index 0000000..e69de29 diff --git a/modules/super_cap/super_cap.md b/modules/super_cap/super_cap.md new file mode 100644 index 0000000..e69de29