diff --git a/Makefile b/Makefile index 59c0c40..bf52eed 100644 --- a/Makefile +++ b/Makefile @@ -14,6 +14,7 @@ # target ###################################### TARGET = basic_framework +SHELL = cmd.exe ###################################### @@ -328,7 +329,7 @@ $(BUILD_DIR)/%.bin: $(BUILD_DIR)/%.elf | $(BUILD_DIR) $(BIN) $< $@ $(BUILD_DIR): - @mkdir $@ + @mkdir $@ ####################################### # clean up diff --git a/application/APP层应用编写指引.md b/application/APP层应用编写指引.md index 9c3f0fc..dd966f9 100644 --- a/application/APP层应用编写指引.md +++ b/application/APP层应用编写指引.md @@ -11,18 +11,33 @@ > 更多关于发布-订阅的实现,请参考`modules/message_center`下的文档。 +## robot_def.h + +这是机器人的参数配置文件,必须要针对每个机器人进行修改。包括机器人的尺寸参数和性能参数等。你还需要在这里设定软硬件配置:云台板/底盘板/单板等。这里定义的宏会作为条件编译的决断。 + +app层共用的状态变量和结构体等也应该定义在这里(例如用于应用之间通信的数据)。记得通信变量要用: +```c +#pragma pack(1) +typedef struct +{ + // your struct + +} your_struct; +#pragma pack() +``` +包裹起来,取消字节对齐以防止出现访问8byte地址而出现错误。 ## robot_cmd -机器人命令模块是对整个机器人的抽象,对于单板控制整车的情况,该应用应该包含接收控制指令的模块,例如遥控器、视觉通信模块。该模块会处理接收到的控制数据,并将其转化为**具体的、定量的**控制信息,发送给其他模块。 +机器人命令模块是对整个机器人的抽象,对于单板控制整车的情况,该应用应该包含接收控制指令的模块,例如遥控器、视觉通信模块。该模块会处理接收到的控制数据,并将其转化为**具体的、定量的**控制信息,发送给其他模块。同时,cmd应用会处理模块和应用离线的情况,出现紧急状况时停止所有执行机构的运行。 如从遥控器获知当前右侧摇杆拨向上方,则将遥控器发来的数值转化为底盘前进的速度值,然后发送给其他应用。同时,robot_cmd还要从其他应用获取反馈信息,做出其他决策。可以将其视为整个机器人的**大脑**。 - +robot_cmd工作起来就像一个遥控数据的兼容层,不论数据的来源是视觉上位机/遥控器/键鼠/图传通信链路/ps手柄,最后都会被转化成真实参考输入提供给其他的app。它的任务是将其他来源的数据映射到控制输入上。 ## gimbal -以步兵为例,云台应用应当包含两个电机,分别用于驱动yaw和pitch轴,还有一个imu(开发板一般放在云台上)。gimbal模块会接收robot_cmd发来的控制信息(云台的角度、转速等),并通过电机提供的接口完成电机的参考值设定。gimbal还要把imu的数据反馈给cmd,用于和视觉的通信以及云台状态的判断。 +以步兵为例,云台应用应当包含两个电机,分别用于驱动yaw和pitch轴(除非你是一个三轴的云台),还有一个imu(开发板一般放在云台上)。gimbal模块会接收robot_cmd发来的控制信息(云台的角度、转速等),并通过电机提供的接口完成电机的参考值设定。gimbal还要把imu的数据反馈给cmd,用于和视觉的通信以及云台状态的判断。 @@ -46,5 +61,5 @@ ## 双板兼容 -此框架对单开发板/双开发板/多开发板的情况都提供了支持(多板一般只在工程机器人上出现,需要自己编写),目前通过条件编译实现了对单双板的切换。使用双板时,主控板在云台上,连接遥控器和上位机;副板在底盘上,负责底盘的运动控制和与裁判系统的通信。 +此框架对单开发板/双开发板/多开发板的情况都提供了支持(多板一般只在工程机器人上出现,需要自己在robot_cmd和robot_def增加相应的条件编译选项,robot.c中也不要忘记增加初始化和任务运行函数),目前通过条件编译实现了对单双板的切换。使用双板时,主控板在云台上,连接遥控器和上位机;副板在底盘上,负责底盘的运动控制和与裁判系统的通信。 diff --git a/application/application.md b/application/application.md index 0cf386f..856982e 100644 --- a/application/application.md +++ b/application/application.md @@ -24,6 +24,8 @@ Robot.c是整个机器人的抽象,其下有4个应用:robot_cmd,gimbal, 为了进一步解耦应用之间的关系,这里并没有采用层级结构(或设计模式中所谓的**工厂模式**,即robot_cmd包含其他三个模块),而采用了应用并列的**发布-订阅**机制,四个应用之间没有任何相互包含关系,他们之间的通信通过module层提供的`message_center`实现。每个应用会通过该模块向一些话题(事件)发布一些消息,同时从一些话题订阅消息。如robot_cmd应用会发布其他三个模块的控制信息,同时订阅其他三个模块的反馈信息。其他三个模块会订阅robot_cmd发布的控制信息,同时发布反馈给robot_cmd的信息,他们不需要知道彼此的存在,只是从`message_center`处获取其他应用发布的消息或向自己发布的话题推送消息。 +application在初始化module的时候,初始化参数会包含部分bsp的内容,但仅仅是外设和引脚的选择以及id设置(用于通信的外设需要id设置)。实际上当前框架的app层和cubemx初始化部分耦合,在配置的时候就必须确定每个外设的作用和归属权,一旦cubemx完成设置app层必须按照对应参数设置引脚和并分配module的外设.后续考虑将cubemx和bsp耦合,去除顶层代码和底层的关系 + ## 整车程序流程 diff --git a/application/robot_def.h b/application/robot_def.h index b27181b..9c6ab16 100644 --- a/application/robot_def.h +++ b/application/robot_def.h @@ -8,7 +8,7 @@ * @copyright Copyright (c) HNU YueLu EC 2022 all rights reserved * */ -#pragma once +#pragma once // 可以用#pragma once代替#ifndef ROBOT_DEF_H(header guard) #ifndef ROBOT_DEF_H #define ROBOT_DEF_H @@ -16,6 +16,7 @@ #include "master_process.h" #include "stdint.h" +// 编译warning,提醒开发者修改机器人参数 #ifndef ROBOT_DEF_PARAM_WARNING #define ROBOT_DEF_PARAM_WARNING #warning BE SURED THAT YOU HAVE ALREADY MODIFIED THESE PARAMETER TO FIT THE ROBOT @@ -27,6 +28,7 @@ // #define GIMBAL_BOARD //云台板 // @todo: 增加机器人类型定义,后续是否要兼容所有机器人?(只兼容步兵英雄哨兵似乎就够了) +// 通过该宏,你可以直接将所有机器人的参数保存在一处,然后每次只需要修改这个宏就可以替换所有参数 /* 机器人类型定义 */ // #define ROBOT_HERO 1 // 英雄机器人 // #define ROBOT_ENINEER 2 // 工程机器人 @@ -52,7 +54,7 @@ #define RADIUS_WHEEL 60 // 轮子半径 #define REDUCTION_RATIO_WHEEL 19.0f // 电机减速比,因为编码器量测的是转子的速度而不是输出轴的速度故需进行转换 -// 检查是否出现定义冲突,只允许一个开发板定义存在,否则编译会自动报错 +// 检查是否出现主控板定义冲突,只允许一个开发板定义存在,否则编译会自动报错 #if (defined(ONE_BOARD) && defined(CHASSIS_BOARD)) || \ (defined(ONE_BOARD) && defined(GIMBAL_BOARD)) || \ (defined(CHASSIS_BOARD) && defined(GIMBAL_BOARD)) diff --git a/bsp/adc/bsp_adc.md b/bsp/adc/bsp_adc.md index 64d4de4..15f222f 100644 --- a/bsp/adc/bsp_adc.md +++ b/bsp/adc/bsp_adc.md @@ -1,3 +1,5 @@ 待添加adc的bsp支持,应该提供阻塞/IT/DMA的量测接口 -是否需要bsp_adc?由于功能非常简单,似乎可以直接使用HAL的接口,没有必要多此一举进行封装? \ No newline at end of file +是否需要bsp_adc?由于功能非常简单,似乎可以直接使用HAL的接口,没有必要多此一举进行封装? + +回调函数. \ No newline at end of file diff --git a/bsp/bsp.md b/bsp/bsp.md index c78fe95..a79783b 100644 --- a/bsp/bsp.md +++ b/bsp/bsp.md @@ -3,12 +3,9 @@ BSP 这是BSP层的说明文档。 > TODO: -> 1. 增加SPI和I2C支持 -> 2. 增加外部中断支持 -> 3. 增加软件中断支持 -> 4. 增加硬件CRC支持 -> 5. 增加USB和虚拟串口支持 +> 1. 增加软件中断支持 +> 2. 增加硬件CRC支持 bsp的功能是提供对片上外设的封装,即单片机芯片内部拥有的功能的封装。在开发板pcb上集成的模块应该放在module层而不是这里。 -bsp应该提供几种接口。包括初始化接口,一般命名为`XXXRegister()`;调用此模块实现的必要功能,如通信型外设(CubeMX下的connectivity)提供接收和发送的接口,以及接收完成的数据回调函数。 \ No newline at end of file +bsp应该提供几种接口。包括初始化接口,一般命名为`XXXRegister()`(对于只有一个instance的可以叫`XXXInit()`,但建议统一风格都叫register);调用此模块实现的必要功能,如通信型外设(CubeMX下的connectivity)提供接收和发送的接口,以及接收完成的数据回调函数。 \ No newline at end of file diff --git a/bsp/bsp_init.c b/bsp/bsp_init.c index 49d5bf2..61887d3 100644 --- a/bsp/bsp_init.c +++ b/bsp/bsp_init.c @@ -11,9 +11,10 @@ void BSPInit() { DWT_Init(168); BSPLogInit(); - USBInit(); // 务必在进入操作系统之前执行USB初始化 + USBInit(); // 务必在进入操作系统之前执行USBInit - // legacy support,待删除,将在实现了led/tempctrl/buzzer的module之后移动到app层 + + // legacy support,待删除,将在实现了led/tempctrl/buzzer的module之后移动到app层进行XXXRegister() LEDInit(); IMUTempInit(); BuzzerInit(); diff --git a/bsp/bsp_legacy_support/legacy.md b/bsp/bsp_legacy_support/legacy.md index ba9001e..42d8db1 100644 --- a/bsp/bsp_legacy_support/legacy.md +++ b/bsp/bsp_legacy_support/legacy.md @@ -1,3 +1,5 @@ # legacy bsp -这些bsp实现将在v0.1删除,因为他们实际上都是用pwm实现的,应当放在module层,以彻底隔离bsp和CubeMX的初始化代码.之后在修改CubeMX的初始化配置之后就不再需要修改bsp的内容了,所有的修改都会通过app层的初始化配置`xxx_Init_Config_s`来实现. \ No newline at end of file +这些bsp实现将在v0.1删除,因为他们实际上都是用pwm实现的,应当放在module层,以彻底隔离bsp和CubeMX的初始化代码.现已提供了bsp_pwm的实现. + +之后在修改CubeMX的初始化配置之后就不再需要修改bsp的内容了,所有的修改都会通过app层的初始化配置`xxx_Init_Config_s`来实现. \ No newline at end of file diff --git a/bsp/can/bsp_can.c b/bsp/can/bsp_can.c index 45272d5..62a7edf 100644 --- a/bsp/can/bsp_can.c +++ b/bsp/can/bsp_can.c @@ -140,7 +140,7 @@ static void CANFIFOxCallback(CAN_HandleTypeDef *_hcan, uint32_t fifox) /** * @brief 注意,STM32的两个CAN设备共享两个FIFO - * 下面两个函数是HAL库中的回调函数,他们声明为__weak,这里对他们进行重载(重写) + * 下面两个函数是HAL库中的回调函数,他们被HAL声明为__weak,这里对他们进行重载(重写) * 当FIFO0或FIFO1溢出时会调用这两个函数 */ // 下面的函数会调用CANFIFOxCallback()来进一步处理来自特定CAN设备的消息 diff --git a/bsp/can/bsp_can.h b/bsp/can/bsp_can.h index c9fdc92..ea10b7a 100644 --- a/bsp/can/bsp_can.h +++ b/bsp/can/bsp_can.h @@ -8,6 +8,7 @@ #define CAN_MX_REGISTER_CNT 16 // 这个数量取决于CAN总线的负载 #define MX_CAN_FILTER_CNT (2 * 14) // 最多可以使用的CAN过滤器数量,目前远不会用到这么多 #define DEVICE_CAN_CNT 2 // 根据板子设定,F407IG有CAN1,CAN2,因此为2;F334只有一个,则设为1 +// 如果只有1个CAN,还需要把bsp_can.c中所有的hcan2变量改为hcan1(别担心,主要是总线和FIFO的负载均衡,不影响功能) /* can instance typedef, every module registered to CAN should have this variable */ #pragma pack(1) diff --git a/bsp/dwt/bsp_dwt.c b/bsp/dwt/bsp_dwt.c index 7dc30ce..1ed3e09 100644 --- a/bsp/dwt/bsp_dwt.c +++ b/bsp/dwt/bsp_dwt.c @@ -6,18 +6,15 @@ * @version V1.1.0 * @date 2022/3/8 * @brief - ****************************************************************************** - * @attention - * - ****************************************************************************** */ + #include "bsp_dwt.h" -DWT_Time_t SysTime; +static DWT_Time_t SysTime; static uint32_t CPU_FREQ_Hz, CPU_FREQ_Hz_ms, CPU_FREQ_Hz_us; static uint32_t CYCCNT_RountCount; static uint32_t CYCCNT_LAST; -uint64_t CYCCNT64; +static uint64_t CYCCNT64; /** * @brief 私有函数,用于检查DWT CYCCNT寄存器是否溢出,并更新CYCCNT_RountCount diff --git a/bsp/dwt/bsp_dwt.h b/bsp/dwt/bsp_dwt.h index d81bb64..5233c09 100644 --- a/bsp/dwt/bsp_dwt.h +++ b/bsp/dwt/bsp_dwt.h @@ -23,7 +23,6 @@ typedef struct uint16_t us; } DWT_Time_t; -extern DWT_Time_t SysTime; /** * @brief 初始化DWT,传入参数为CPU频率,单位MHz diff --git a/bsp/dwt/bsp_dwt.md b/bsp/dwt/bsp_dwt.md index f936bd0..f5cc516 100644 --- a/bsp/dwt/bsp_dwt.md +++ b/bsp/dwt/bsp_dwt.md @@ -1,3 +1,3 @@ # bsp_dwt -DWT是stm32内部的一个"隐藏资源",他的用途是给下载器提供准确的定时,从而为调试信息加上时间戳. \ No newline at end of file +DWT是stm32内部的一个"隐藏资源",他的用途是给下载器提供准确的定时,从而为调试信息加上时间戳.并在固定的时间间隔将调试数据发送到你的xxlink上. \ No newline at end of file diff --git a/bsp/gpio/bsp_gpio.md b/bsp/gpio/bsp_gpio.md index d58df0d..6c8ae5d 100644 --- a/bsp/gpio/bsp_gpio.md +++ b/bsp/gpio/bsp_gpio.md @@ -6,9 +6,11 @@ ![img](../../assets/00937839b59a4c039ee8ecb8a5136e3c.png) + 使用示例 ```c +//在app层只需要设置前三个,callback由module自动设置 GPIO_Init_Config_s gpio_init = { .exti_mode = GPIO_EXTI_MODE_FALLING, // 注意和CUBEMX的配置一致 @@ -19,4 +21,5 @@ GPIO_Init_Config_s gpio_init = { GPIOInstance* test_example = GPIORegister(&gpio_init); GPIOSet(test_example); +// GPIOxxx(test_exmaple, ...); ``` \ No newline at end of file diff --git a/bsp/iic/bsp_iic.c b/bsp/iic/bsp_iic.c index fa6168e..bc683ae 100644 --- a/bsp/iic/bsp_iic.c +++ b/bsp/iic/bsp_iic.c @@ -70,7 +70,7 @@ void IICReceive(IICInstance *iic, uint8_t *data, uint16_t size, IIC_Seq_Mode_e s { if (seq_mode != IIC_RELEASE && seq_mode != IIC_HOLD_ON) while (1) - ; // 未知传输模式, 程序停止 + ; // 未知传输模式, 程序停止,请检查指针越界 // 初始化接收缓冲区地址以及接受长度, 用于中断回调函数 iic->rx_buffer = data; @@ -140,7 +140,7 @@ void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c) } /** - * @brief 仅做形式上的封装,仍然使用HAL_I2C_MasterRxCpltCallback + * @brief 内存访问回调函数,仅做形式上的封装,仍然使用HAL_I2C_MasterRxCpltCallback * * @param hi2c handle */ diff --git a/bsp/iic/bsp_iic.md b/bsp/iic/bsp_iic.md index c317815..e7e5be1 100644 --- a/bsp/iic/bsp_iic.md +++ b/bsp/iic/bsp_iic.md @@ -4,4 +4,7 @@ https://blog.csdn.net/NeoZng/article/details/128496694 -https://blog.csdn.net/NeoZng/article/details/128486366 \ No newline at end of file +https://blog.csdn.net/NeoZng/article/details/128486366 + + +使用序列通信则在单次通信后不会释放总线,继续占用直到调用传输函数时传入`IIC_RELEASE`参数. 这个功能只在一条总线上挂载多个主机的时候有用. \ No newline at end of file diff --git a/bsp/pwm/bsp_pwm.c b/bsp/pwm/bsp_pwm.c index eb51aca..410992b 100644 --- a/bsp/pwm/bsp_pwm.c +++ b/bsp/pwm/bsp_pwm.c @@ -6,6 +6,11 @@ static uint8_t idx; static PWMInstance *pwm_instance[PWM_DEVICE_CNT] = {NULL}; // 所有的pwm instance保存于此,用于callback时判断中断来源 +/** + * @brief pwm dma传输完成回调函数 + * + * @param htim 发生中断的定时器句柄 + */ void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim) { for (uint8_t i = 0; i < idx; i++) diff --git a/bsp/pwm/bsp_pwm.h b/bsp/pwm/bsp_pwm.h index 654e9a3..d18f967 100644 --- a/bsp/pwm/bsp_pwm.h +++ b/bsp/pwm/bsp_pwm.h @@ -1,3 +1,15 @@ +/** + * @file bsp_pwm.h + * @author your name (you@domain.com) + * @brief + * @version 0.1 + * @date 2023-02-14 + * @todo 目前的实现有比较大的问题,是否允许module修改tim的分频器和自动重装载寄存器? + * + * @copyright Copyright (c) 2023 + * + */ + #ifndef BSP_PWM_H #define BSP_PWM_H @@ -52,7 +64,8 @@ void PWMStart(PWMInstance *pwm); */ void PWMStop(PWMInstance *pwm); -// @todo 这三个函数还需要进一步封装,协调好三者之间的关系 + +// @todo 这三个函数还需要进一步封装,务必协调好三者之间的关系 /** * @brief 设置pwm脉宽 * diff --git a/bsp/spi/bsp_spi.h b/bsp/spi/bsp_spi.h index 4980116..14f0cf3 100644 --- a/bsp/spi/bsp_spi.h +++ b/bsp/spi/bsp_spi.h @@ -32,6 +32,7 @@ typedef struct spi_ins_temp /* 接收回调函数定义,包含SPI的module按照此格式构建回调函数 */ typedef void (*spi_rx_callback)(SPIInstance *); +// @todo: 这里可以将GPIO_TypeDef *GPIO_cs; uint16_t cs_pin合并为bsp_gpio以简化代码实现 /* SPI初始化配置,其实基本和SPIIstance一模一样,为了代码风格统一因此再次定义 */ typedef struct { diff --git a/bsp/usart/bsp_usart.h b/bsp/usart/bsp_usart.h index bde0667..34e74db 100644 --- a/bsp/usart/bsp_usart.h +++ b/bsp/usart/bsp_usart.h @@ -17,7 +17,8 @@ typedef enum USART_TRANSFER_RX, } USART_TRANSFER_MODE; -// 串口实例结构体,每个module都要包含一个实例 +// 串口实例结构体,每个module都要包含一个实例. +// 由于串口是独占的点对点通信,所以不需要考虑多个module同时使用一个串口的情况,因此不用加入id;当然也可以选择加入,这样在bsp层可以访问到module的其他信息 typedef struct { uint8_t recv_buff[USART_RXBUFF_LIMIT]; // 预先定义的最大buff大小,如果太小请修改USART_RXBUFF_LIMIT @@ -44,7 +45,9 @@ USARTInstance *USARTRegister(USART_Init_Config_s *init_config); /** * @brief 通过调用该函数可以发送一帧数据,需要传入一个usart实例,发送buff以及这一帧的长度 * 当前默认为DMA发送,后续会增加中断发送和阻塞发送模式的选择 - * + * @todo 目前只支持DMA发送,后续会增加中断发送和阻塞发送模式的选择 + * 在短时间内连续调用此接口会导致上一次的发送未完成而新的发送取消,后续会增加一个发送状态的判断以及消息队列以解决这个问题 + * * @param _instance 串口实例 * @param send_buf 待发送数据的buffer * @param send_size how many bytes to send diff --git a/bsp/usart/bsp_usart.md b/bsp/usart/bsp_usart.md index 5f90ad4..5923336 100644 --- a/bsp/usart/bsp_usart.md +++ b/bsp/usart/bsp_usart.md @@ -2,7 +2,8 @@
neozng1@hnu.edu.cn
-> TODO:为初始化定义一个结构体`usart_init_config`用于保存初始化所需的参数从而避免单独赋值,使得整体风格统一。 +> TODO: 增加发送队列以解决短时间内调用`USARTSend()`发生丢包的问题,并提供阻塞和IT模式以供选择 +> 可以直接在发送函数的参数列表添加发送模式选择,或增加instance成员变量,并提供设置模式接口,两者各有优劣 ## 使用说明 diff --git a/bsp/usb/bsp_usb.h b/bsp/usb/bsp_usb.h index 61753b7..4ee7af2 100644 --- a/bsp/usb/bsp_usb.h +++ b/bsp/usb/bsp_usb.h @@ -3,7 +3,7 @@ * @author your name (you@domain.com) * @brief 提供对usb vpc(virtal com port)的操作接口,hid和msf考虑后续添加 * @todo 与usart的接口统一完成兼容 - * @attention 这一版修改了usbd_cdc_if.c中的CDC_Receive_FS函数,cube生成后会被覆盖.后续需要由usbcdciftemplate创建一套自己的模板 + * @attention 这一版usb修改了usbd_cdc_if.c中的CDC_Receive_FS函数,若使用cube生成后会被覆盖.后续需要由usbcdciftemplate创建一套自己的模板 * @version 0.1 * @date 2023-02-09 * diff --git a/modules/BMI088/bmi088.c b/modules/BMI088/bmi088.c index 03eb0d4..278eb7b 100644 --- a/modules/BMI088/bmi088.c +++ b/modules/BMI088/bmi088.c @@ -379,6 +379,7 @@ void BMI088CalibrateIMU(BMI088Instance *_bmi088) fabsf(_bmi088->gyro_offset[2]) > 0.01f); // 满足条件说明标定环境不好 } + // 离线标定 if (_bmi088->cali_mode == BMI088_LOAD_PRE_CALI_MODE) // 如果标定失败也会进来,直接使用离线数据 { // 读取标定数据 @@ -408,6 +409,7 @@ BMI088Instance *BMI088Register(BMI088_Init_Config_s *config) config->spi_gyro_config.id = config->heat_pwm_config.id = bmi088_instance; + // @todo: // 目前只实现了!!!阻塞读取模式!!!.如果需要使用IT模式,则需要修改这里的代码,为spi和gpio注册callback(默认为NULL) // 还需要设置SPI的传输模式为DMA模式或IT模式(默认为blocking) // 可以通过conditional compilation或者runtime参数判断 diff --git a/modules/BMI088/bmi088.h b/modules/BMI088/bmi088.h index 25a2144..8d6ef53 100644 --- a/modules/BMI088/bmi088.h +++ b/modules/BMI088/bmi088.h @@ -29,8 +29,8 @@ typedef struct float acc[3]; // 加速度计数据,xyz float temperature; // 温度 - // uint32_t timestamp; // 时间戳 - // uint32_t count; + // float timestamp; // 时间戳,单位为ms,用于计算两次采样的时间间隔,同时给视觉提供timeline + // uint32_t count; // 第count次采样,用于对齐时间戳 } BMI088_Data_t; #pragma pack() // 恢复默认对齐,需要传输的结构体务必开启1字节对齐 @@ -107,7 +107,8 @@ BMI088Instance *BMI088Register(BMI088_Init_Config_s *config); BMI088_Data_t BMI088Acquire(BMI088Instance *bmi088); /** - * @brief 标定传感器 + * @brief 标定传感器.BMI088在初始化的时候会调用此函数. 提供接口方便标定离线数据 + * @attention @todo 注意,当操作系统开始运行后,此函数会和INS_Task冲突.目前不允许在运行时调用此函数,后续加入标志位判断以提供运行时重新的标定功能 * * @param _bmi088 待标定的实例 */ diff --git a/modules/BMI088/bmi088.md b/modules/BMI088/bmi088.md index a877b29..2adb716 100644 --- a/modules/BMI088/bmi088.md +++ b/modules/BMI088/bmi088.md @@ -47,6 +47,7 @@ write写入: 温度数据不需要和accel和gyro同步,它不参与姿态解算,可以不用管. 当加速度数据和陀螺仪数据都准备完成之后,唤醒姿态解算任务INs_taSk,进行一次解算.唤醒可以通过软件开启EXTI中断,在中断中调用实时系统的vTaskNotifyFromISR()完成,也可以将任务ready标志位置位,当运行到对应位置时检查标志位判断是否要进行任务.时间间隔不是大问题,inS_TAsK中有dwt用于计算两次任务执行的间隔,它将会自动处理好bias的大小 -`__HAL_GPIO_EXTI_GENERATE_SWIT()` `HAL_EXTI_GENERATE_SWI()` + +`__HAL_GPIO_EXTI_GENERATE_SWIT()` `HAL_EXTI_GENERATE_SWI()` 可以触发软件中断 of course,两者的数据更新实际上可以异步进行,这里为了方便起见当两者数据都准备好以后再行融合 diff --git a/modules/BMI088/bmi088_regNdef.h b/modules/BMI088/bmi088_regNdef.h index b548a9f..b108bc1 100644 --- a/modules/BMI088/bmi088_regNdef.h +++ b/modules/BMI088/bmi088_regNdef.h @@ -1,7 +1,7 @@ #ifndef BMI088REG_H #define BMI088REG_H -/*------- BMI088寄存器地址和内容-------*/ +/*------- BMI088寄存器地址及其存放的内容-------*/ #define BMI088_ACC_CHIP_ID 0x00 // the register is " Who am I " #define BMI088_ACC_CHIP_ID_VALUE 0x1E @@ -125,7 +125,7 @@ #define BMI088_GYRO_125 (0x4 << BMI088_GYRO_RANGE_SHFITS) #define BMI088_GYRO_BANDWIDTH 0x10 -// the first num means Output data rate, the second num means bandwidth +// the first num means Output data rate, the second num means bandwidth #define BMI088_GYRO_BANDWIDTH_MUST_Set 0x80 #define BMI088_GYRO_2000_532_HZ 0x00 #define BMI088_GYRO_2000_230_HZ 0x01 diff --git a/modules/algorithm/LQR.c b/modules/algorithm/LQR.c index e69de29..a59e79e 100644 --- a/modules/algorithm/LQR.c +++ b/modules/algorithm/LQR.c @@ -0,0 +1 @@ +#include "LQR.h" diff --git a/modules/algorithm/LQR.h b/modules/algorithm/LQR.h index e69de29..0a1675b 100644 --- a/modules/algorithm/LQR.h +++ b/modules/algorithm/LQR.h @@ -0,0 +1,12 @@ +/** + * @file LQR.h + * @author your name (you@domain.com) + * @brief 利用arm math库实现矩阵运算功能 + * @version 0.1 + * @date 2023-02-14 + * + * @copyright Copyright (c) 2023 + * + */ + +#pragma once \ No newline at end of file diff --git a/modules/can_comm/can_comm.h b/modules/can_comm/can_comm.h index aaf5045..636dfba 100644 --- a/modules/can_comm/can_comm.h +++ b/modules/can_comm/can_comm.h @@ -71,7 +71,7 @@ void CANCommSend(CANCommInstance *instance, uint8_t *data); * @return void* 返回的数据指针 * @attention 注意如果希望直接通过转换指针访问数据,如果数据是union或struct,要检查是否使用了pack(n) * CANComm接收到的数据可以看作是pack(1)之后的,是连续存放的. - * 如果使用了pack(n)可能会导致数据错乱,并且无法使用强制类型转换直接访问,而需要手动解包. + * 如果使用了pack(n)可能会导致数据错乱,并且无法使用强制类型转换通过memcpy直接访问,转而需要手动解包. * 强烈建议通过CANComm传输的数据使用pack(1) */ void *CANCommGet(CANCommInstance *instance); diff --git a/modules/general_def.h b/modules/general_def.h index e99a397..b5bba74 100644 --- a/modules/general_def.h +++ b/modules/general_def.h @@ -1,6 +1,9 @@ #ifndef GENERAL_DEF_H #define GENERAL_DEF_H +// 一些module的通用数值型定义,注意条件macro兼容,一些宏可能在math.h中已经定义过了 + + #ifndef PI #define PI 3.1415926535f #endif // !PI diff --git a/modules/imu/ins_task.md b/modules/imu/ins_task.md index 26889f4..7fd972a 100644 --- a/modules/imu/ins_task.md +++ b/modules/imu/ins_task.md @@ -11,4 +11,5 @@ ## 模块移植 -由于历史遗留问题,IMU模块耦合程度高.后续实现BSP_SPI,将bmi088 middleware删除.仅保留BMI088读取的协议和寄存器定义等,单独实现IMU模块. \ No newline at end of file +由于历史遗留问题,IMU模块耦合程度高.后续实现BSP_SPI,将bmi088 middleware删除.仅保留BMI088读取的协议和寄存器定义等,单独实现IMU模块. +> 移植已经完成,请转而使用module/BMI088的模块. 当前文件夹将在beta1.2停止支持, 1.5之后删除. INS_Task届时会被放到algorithm中,以提供对不同IMU的兼容. \ No newline at end of file diff --git a/modules/ist8310/ist8310.md b/modules/ist8310/ist8310.md index d89ee0f..b90ad21 100644 --- a/modules/ist8310/ist8310.md +++ b/modules/ist8310/ist8310.md @@ -21,6 +21,7 @@ IST8310_Init_Config_s ist8310_conf = { .work_mode = IIC_BLOCK_MODE, }, }; + IST8310Instance *asdf = IST8310Init(&ist8310_conf); // 随后数据会被放到asdf.mag[i]中 diff --git a/modules/oled/oled.h b/modules/oled/oled.h index 078ac42..f1bb53d 100644 --- a/modules/oled/oled.h +++ b/modules/oled/oled.h @@ -1,3 +1,15 @@ +/** + * @file oled.h + * @author your name (you@domain.com) + * @brief 待重构实现 + * @version 0.1 + * @date 2023-02-14 + * @todo 请重构show string/init/clean/update buffer等的实现 + * + * @copyright Copyright (c) 2023 + * + */ + #ifndef OLED_H #define OLED_H #include