重新组织了文件的防止

This commit is contained in:
NeoZng 2023-01-02 23:20:35 +08:00
parent c05513587c
commit bfaae13b59
26 changed files with 105 additions and 62 deletions

View File

@ -88,7 +88,7 @@ to exclude the API function. */
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 0
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1

View File

@ -124,11 +124,11 @@ modules/imu/ins_task.c \
modules/led/led_task.c \
modules/master_machine/master_process.c \
modules/master_machine/seasky_protocol.c \
modules/motor/dji_motor.c \
modules/motor/HT04.c \
modules/motor/LK9025.c \
modules/motor/step_motor.c \
modules/motor/servo_motor.c \
modules/motor/DJImotor/dji_motor.c \
modules/motor/HTmotor/HT04.c \
modules/motor/LKmotor/LK9025.c \
modules/motor/step_motor/step_motor.c \
modules/motor/servo_motor/servo_motor.c \
modules/motor/motor_task.c \
modules/referee/crc.c \
modules/referee/referee.c \
@ -238,6 +238,11 @@ C_INCLUDES = \
-Imodules/imu \
-Imodules/led \
-Imodules/master_machine \
-Imodules/motor/DJImotor \
-Imodules/motor/LKmotor \
-Imodules/motor/HTmotor \
-Imodules/motor/step_motor \
-Imodules/motor/servo_motor \
-Imodules/motor \
-Imodules/referee \
-Imodules/remote \

View File

@ -103,7 +103,6 @@
// 接收的回调函数,用于解析接收到的数据
void (*can_module_callback)(struct _ *); // callback needs an instance to tell among registered ones
} CANInstance;
#pragma pack()
```
@ -111,13 +110,11 @@
## BSP层(Board Sopport Package)
- TODO
1. 增加SPI和I^2^C的BSP模组以便支持IST384磁力计和Oled显示屏等。
1. 增加和module层的deteck_task配合的蜂鸣器和led闪烁配置。
- 主要功能:实现映射功能。
- 在本框架中BSP层与cube高度耦合对该层的修改可能需要使用cube重新生成工程主要是外设的配置通信速度时钟频率和分频数等。该层也是唯一允许直接出现stm32HAL库函数的代码层**在非BSP层编写代码时如需使用HAL_...函数请思考是否有同功能的BSP_...函数**。不过由于ST的HAL已经对硬件进行较高的抽象如以handle_xxx的方式描述一个硬件外设或功能引脚因此更换开发板需要修改的内容极少。
- 最简单的(如gpio)仅是对HAL库函数的封装。较为复杂的则会进行一定程度的处理(如can)
- 补充与修改某款主控对应的BSP层应保持相同当认为该层可能缺少部分功能或有错误时请联系组长确认后解决并更新整个框架**请勿自行修改**。
- 代码移植BSP层也是在不同系列、型号的stm32间执行代码移植时主要需要关注的代码层。向功能更强系列移植一般只需要重配cube并重新组织BSP层的映射关系而向功能较少的系列移植还需要去掉其不支持的功能。修改BSP后一般不需要对其他两层进行修改
- 代码移植BSP层也是在不同系列、型号的stm32间执行代码移植时主要需要关注的代码层。向功能更强系列移植一般只需要重配cube并重新组织BSP层的映射关系而向功能较少的系列移植还需要去掉其不支持的功能。如果仅是对同一型号的开发板进行HAL初始化配置的修改则BSP层**不需要**变动
- 子文件与文件夹:
- bsp.c/h该层核心文件其中.h被include至main.c中以实现整个代码层的初始化。include了该层所有模块的.h并调用各模块的初始化函数。**注意**有些外设如串口和CAN不需要在bsp.c中进行模块层的初始化他们会在module层生成实例即C语言中的结构体并注册到bsp层时自动进行初始化。以此达到提高运行速度避免未使用的模块被加载的问题。
- bsp_xxx.c/h每一个成对的.c/h对应一种外设当上面两个代码层需要使用某个外设时这里的文件就是对应的交互接口。
@ -128,7 +125,6 @@
- TODO
1. 增加模块离线/错误检测模块(官方例程中的`deteck_task`)。
2. 增加超级电容模块
3. 增加步进电机模块
4. 增加裁判系统多机通信、UI绘制模块
5. 增加舵机模块
@ -138,7 +134,7 @@
- 子文件与子文件夹
- **注意module层没有也不需要进行同意初始化**。app层的应用会包含一些模块因此由app来调用各个模块的init或register函数只有当一个module被app实例化这个模块才会存在。
- **注意module层没有也不需要进行统一初始化**。app层的应用会包含一些模块因此由app来调用各个模块的init或register函数只有当一个module被app实例化这个模块才会存在。
> 命名为init()的初始化一般来说是开发板的独占资源即有且只有一个这样的模块无法拥有多个实例如板载陀螺仪、LED、按键等。命名为register()的模块则可以拥有多个,比如电机。

View File

@ -5,7 +5,7 @@
#include "message_center.h"
#include "general_def.h"
static attitude_t *Gimbal_IMU_data; // 云台IMU数据
static attitude_t *gimba_IMU_data; // 云台IMU数据
static DJIMotorInstance *yaw_motor; // yaw电机
static DJIMotorInstance *pitch_motor; // pitch电机
@ -16,7 +16,7 @@ static Gimbal_Ctrl_Cmd_s gimbal_cmd_recv; // 来自cmd的控制信息
void GimbalInit()
{
// Gimbal_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源
gimba_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源
// YAW
Motor_Init_Config_s yaw_config = {
@ -38,9 +38,9 @@ void GimbalInit()
.Kd = 0,
.MaxOut = 4000,
},
.other_angle_feedback_ptr = &Gimbal_IMU_data->YawTotalAngle,
// 还需要增加角速度额外反馈指针
// .other_speed_feedback_ptr=&Gimbal_IMU_data.wz;
.other_angle_feedback_ptr = &gimba_IMU_data->YawTotalAngle,
// 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明
// .other_speed_feedback_ptr=&gimba_IMU_data.wz;
},
.controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED,
@ -70,9 +70,9 @@ void GimbalInit()
.Kd = 0,
.MaxOut = 4000,
},
.other_angle_feedback_ptr = &Gimbal_IMU_data->Pitch,
// 还需要增加角速度额外反馈指针
// .other_speed_feedback_ptr=&Gimbal_IMU_data.wy,
.other_angle_feedback_ptr = &gimba_IMU_data->Pitch,
// 还需要增加角速度额外反馈指针,注意方向,ins_task.md中有c板的bodyframe坐标系说明
// .other_speed_feedback_ptr=&gimba_IMU_data.wy,
},
.controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED,
@ -133,7 +133,7 @@ void GimbalTask()
}
// 设置反馈数据,主要是imu和yaw的ecd
gimbal_feedback_data.gimbal_imu_data = *Gimbal_IMU_data;
gimbal_feedback_data.gimbal_imu_data = *gimba_IMU_data;
gimbal_feedback_data.yaw_motor_single_round_angle = yaw_motor->motor_measure.angle_single_round;
// 推送消息

View File

@ -163,7 +163,8 @@ Dma.USART6_TX.1.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.USART6_TX.1.PeriphInc=DMA_PINC_DISABLE
Dma.USART6_TX.1.Priority=DMA_PRIORITY_HIGH
Dma.USART6_TX.1.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority,FIFOMode
FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configMAX_TASK_NAME_LEN,configUSE_TIMERS,configUSE_POSIX_ERRNO
FREERTOS.INCLUDE_vTaskDelayUntil=1
FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configMAX_TASK_NAME_LEN,configUSE_TIMERS,configUSE_POSIX_ERRNO,INCLUDE_vTaskDelayUntil
FREERTOS.Tasks01=defaultTask,0,128,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL
FREERTOS.configENABLE_FPU=1
FREERTOS.configMAX_TASK_NAME_LEN=32

View File

@ -101,4 +101,6 @@ void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan)
- `CANAddFilter()`在每次使用`CANRegister()`的时候被调用,用于给当前注册的实例添加过滤器规则并设定处理对应`rx_id`的接收FIFO。过滤器的作用是减小CAN收发器的压力只接收符合过滤器规则的报文否则不会产生接收中断
- `HAL_CAN_RxFifo0MsgPendingCallback()`和`HAL_CAN_RxFifo1MsgPendingCallback()`都是对HAL的CAN回调函数的重定义原本的callback是`__week`修饰的弱定义当发生FIFO0或FIFO1有新消息到达的时候对应的callback会被调用。`CANFIFOxCallback()`随后被前两者调用并根据接收id和硬件中断来源哪一个CAN硬件CAN1还是CAN2调用对应的instance的回调函数进行协议解析。
- `HAL_CAN_RxFifo0MsgPendingCallback()`和`HAL_CAN_RxFifo1MsgPendingCallback()`都是对HAL的CAN回调函数的重定义原本的callback是`__week`修饰的弱定义当发生FIFO0或FIFO1有新消息到达的时候对应的callback会被调用。`CANFIFOxCallback()`随后被前两者调用并根据接收id和硬件中断来源哪一个CAN硬件CAN1还是CAN2调用对应的instance的回调函数进行协议解析。
- 当有一个模块注册了多个can实例时通过`CANInstance.id`,使用强制类型转换将其转换成对应模块的实例指针,就可以对不同的模块实例进行回调处理了。

View File

@ -55,6 +55,7 @@ SPIInstance *SPIRegister(SPI_Init_Config_s *conf);
/**
* @brief spi向对应从机发送数据
* @todo timeout参数
*
* @param spi_ins spi实例指针
* @param ptr_data
@ -73,7 +74,8 @@ void SPIRecv(SPIInstance *spi_ins, uint8_t *ptr_data, uint8_t len);
/**
* @brief spi利用移位寄存器同时收发数据
*
* @todo timeout参数
*
* @param spi_ins spi实例指针
* @param ptr_data_rx
* @param ptr_data_tx

View File

@ -1,17 +1,48 @@
#ifndef __BMI088_H__
#define __BMI088_H__
#include "bsp_spi.h"
#include "controller.h"
#include "bsp_pwm.h"
#include "stdint.h"
typedef enum
{
BMI088_CALIBRATE_MODE = 0, // 初始化时进行标定
BMI088_LOAD_PRE_CALI_MODE, // 使用预设标定参数
} BMI088_Work_Mode_e;
/* BMI088实例结构体定义 */
typedef struct
{
SPIInstance *spi_gyro;
// 传输模式和工作模式控制
SPIInstance *spi_gyro;
SPIInstance *spi_acc;
// 温度控制
PIDInstance *heat_pid; // 恒温PID
PWMInstance *heat_pwm; // 加热PWM
// IMU数据
float gyro[3]; // 陀螺仪数据,xyz
float acc[3]; // 加速度计数据,xyz
float temperature; // 温度
// 标定数据
float gyro_offset[3]; // 陀螺仪零偏
float gNorm; // 重力加速度模长,从标定获取
float acc_coef; // 加速度计原始数据转换系数
// 用于计算两次采样的时间间隔
uint32_t bias_dwt_cnt;
} BMI088Instance;
/* BMI088初始化配置 */
typedef struct
{
SPI_Init_Config_s spi_gyro_config;
SPI_Init_Config_s spi_acc_config;
BMI088_Work_Mode_e mode;
PID_Init_Config_s heat_pid_config;
PWM_Init_Config_s heat_pwm_config;
} BMI088_Init_Config_s;
}BMI088_Init_Config_s;
#endif // !__BMI088_H__

View File

@ -126,14 +126,14 @@ static void f_PID_ErrorHandle(PIDInstance *pid)
* @param pid PID实例
* @param config PID初始化设置
*/
void PID_Init(PIDInstance *pid, PID_Init_config_s *config)
void PID_Init(PIDInstance *pid, PID_Init_Config_s *config)
{
// config的数据和pid的部分数据是连续且相同的的,所以可以直接用memcpy
// @todo: 不建议这样做,可扩展性差,不知道的开发者可能会误以为pid和config是同一个结构体
// 后续修改为逐个赋值
memset(pid, 0, sizeof(PIDInstance));
// utilize the quality of struct that its memeory is continuous
memcpy(pid, config, sizeof(PID_Init_config_s));
memcpy(pid, config, sizeof(PID_Init_Config_s));
// set rest of memory to 0
}

View File

@ -28,7 +28,7 @@
// PID 优化环节使能标志位
typedef enum
{
PID_IMPROVE_NONE = 0b00000000, // 0000 0000
PID_IMPROVE_NONE = 0b00000000, // 0000 0000
Integral_Limit = 0b00000001, // 0000 0001
Derivative_On_Measurement = 0b00000010, // 0000 0010
Trapezoid_Intergral = 0b00000100, // 0000 0100
@ -112,7 +112,7 @@ typedef struct
float Derivative_LPF_RC;
PID_Improvement_e Improve;
} PID_Init_config_s;
} PID_Init_Config_s;
/**
* @brief PID实例
@ -120,7 +120,7 @@ typedef struct
* @param pid PID实例指针
* @param config PID初始化配置
*/
void PID_Init(PIDInstance *pid, PID_Init_config_s *config);
void PID_Init(PIDInstance *pid, PID_Init_Config_s *config);
/**
* @brief PID输出

View File

@ -3,13 +3,12 @@
#ifndef PI
#define PI 3.1415926535f
#endif // !PI
#endif // !PI
#define PI2 (PI * 2.0f) // 2 pi
#define RAD_2_ANGLE (180.0f / PI)
#define ANGLE_2_RAD (PI / 180.0f)
#define RPM_2_ANGLE_PER_SEC (360.0f/60.0f) // ×360°/60sec
#define RAD_2_ANGLE 57.2957795f // 180/pi
#define ANGLE_2_RAD 0.01745329252f // pi/180
#define RPM_2_ANGLE_PER_SEC 6.0f // ×360°/60sec
#endif // !GENERAL_DEF_H

View File

@ -57,7 +57,7 @@ attitude_t *INS_Init(void)
IMU_QuaternionEKF_Init(10, 0.001, 10000000, 1, 0);
// imu heat init
PID_Init_config_s config = {.MaxOut = 2000,
PID_Init_Config_s config = {.MaxOut = 2000,
.IntegralLimit = 300,
.DeadBand = 0,
.Kp = 1000,
@ -68,7 +68,7 @@ attitude_t *INS_Init(void)
// noise of accel is relatively big and of high freq,thus lpf is used
INS.AccelLPF = 0.0085;
return (attitude_t*)&INS.Roll;
return (attitude_t*)&INS.Gyro; // @todo: 这里偷懒了,不要这样做! 修改INT_t结构体可能会导致异常,待修复.
}
/* 注意以1kHz的频率运行此任务 */
@ -96,8 +96,8 @@ void INS_Task(void)
IMU_Param_Correction(&IMU_Param, INS.Gyro, INS.Accel);
// 计算重力加速度矢量和b系的XY两轴的夹角,可用作功能扩展,本demo暂时没用
INS.atanxz = -atan2f(INS.Accel[X], INS.Accel[Z]) * 180 / PI;
INS.atanyz = atan2f(INS.Accel[Y], INS.Accel[Z]) * 180 / PI;
// INS.atanxz = -atan2f(INS.Accel[X], INS.Accel[Z]) * 180 / PI;
// INS.atanyz = atan2f(INS.Accel[Y], INS.Accel[Z]) * 180 / PI;
// 核心函数,EKF更新四元数
IMU_QuaternionEKF_Update(INS.Gyro[X], INS.Gyro[Y], INS.Gyro[Z], INS.Accel[X], INS.Accel[Y], INS.Accel[Z], dt);

View File

@ -9,7 +9,7 @@
******************************************************************************
* @attention INS任务的初始化不要放入实时系统!application拥有实例,
* .
*
*
******************************************************************************
*/
#ifndef __INS_TASK_H
@ -27,32 +27,36 @@
typedef struct
{
float Gyro[3]; // 角速度
float Accel[3]; // 加速度
// 还需要增加角速度数据
float Roll;
float Pitch;
float Yaw;
float YawTotalAngle;
} attitude_t; //最终解算得到的角度,以及yaw转动的总角度(方便多圈控制)
} attitude_t; // 最终解算得到的角度,以及yaw转动的总角度(方便多圈控制)
typedef struct
{
float q[4]; // 四元数估计值
float Gyro[3]; // 角速度
float Accel[3]; // 加速度
float MotionAccel_b[3]; // 机体坐标加速度
float MotionAccel_n[3]; // 绝对系加速度
float AccelLPF; // 加速度低通滤波系数
// 加速度在绝对系的向量表示
// bodyframe在绝对系的向量表示
float xn[3];
float yn[3];
float zn[3];
float atanxz;
float atanyz;
// 加速度在机体系和XY两轴的夹角
// float atanxz;
// float atanyz;
// IMU量测值
float Gyro[3]; // 角速度
float Accel[3]; // 加速度
// 位姿
float Roll;
float Pitch;

View File

@ -38,7 +38,8 @@ static uint8_t sender_enable_flag[6] = {0};
*/
static void IDcrash_Handler(uint8_t conflict_motor_idx, uint8_t temp_motor_idx)
{
while (1);
while (1)
;
}
/**
@ -46,13 +47,13 @@ static void IDcrash_Handler(uint8_t conflict_motor_idx, uint8_t temp_motor_idx)
*
* @param config
*/
static void MotorSenderGrouping(CAN_Init_Config_s *config)
static void MotorSenderGrouping(DJIMotorInstance *motor, CAN_Init_Config_s *config)
{
uint8_t motor_id = config->tx_id - 1; // 下标从零开始,先减一方便赋值
uint8_t motor_send_num;
uint8_t motor_grouping;
switch (dji_motor_instance[idx]->motor_type)
switch (motor->motor_type)
{
case M2006:
case M3508:
@ -70,8 +71,8 @@ static void MotorSenderGrouping(CAN_Init_Config_s *config)
// 计算接收id并设置分组发送id
config->rx_id = 0x200 + motor_id + 1;
sender_enable_flag[motor_grouping] = 1;
dji_motor_instance[idx]->message_num = motor_send_num;
dji_motor_instance[idx]->sender_group = motor_grouping;
motor->message_num = motor_send_num;
motor->sender_group = motor_grouping;
// 检查是否发生id冲突
for (size_t i = 0; i < idx; ++i)
@ -95,8 +96,8 @@ static void MotorSenderGrouping(CAN_Init_Config_s *config)
config->rx_id = 0x204 + motor_id + 1;
sender_enable_flag[motor_grouping] = 1;
dji_motor_instance[idx]->message_num = motor_send_num;
dji_motor_instance[idx]->sender_group = motor_grouping;
motor->message_num = motor_send_num;
motor->sender_group = motor_grouping;
for (size_t i = 0; i < idx; ++i)
{
@ -106,7 +107,8 @@ static void MotorSenderGrouping(CAN_Init_Config_s *config)
break;
default: // other motors should not be registered here
while(1); // 其他电机不应该在这里注册
while (1)
; // 其他电机不应该在这里注册
}
}
@ -161,11 +163,11 @@ DJIMotorInstance *DJIMotorInit(Motor_Init_Config_s *config)
instance->motor_controller.other_speed_feedback_ptr = config->controller_param_init_config.other_speed_feedback_ptr;
// 电机分组,因为至多4个电机可以共用一帧CAN控制报文
MotorSenderGrouping(&config->can_init_config);
MotorSenderGrouping(instance, &config->can_init_config);
// 注册电机到CAN总线
config->can_init_config.can_module_callback = DecodeDJIMotor; // set callback
config->can_init_config.id = instance;// set id,eq to address(it is identity)
config->can_init_config.id = instance; // set id,eq to address(it is identity)
instance->motor_can_instance = CANRegister(&config->can_init_config);
DJIMotorEnable(instance);

View File

@ -18,6 +18,7 @@
#include "bsp_can.h"
#include "controller.h"
#include "motor_def.h"
#include "stdint.h"
#define DJI_MOTOR_CNT 12

View File

@ -115,9 +115,9 @@ typedef struct
float *speed_feedforward_ptr; // 速度前馈数据指针
float *current_feedforward_ptr; // 电流前馈数据指针
PID_Init_config_s current_PID;
PID_Init_config_s speed_PID;
PID_Init_config_s angle_PID;
PID_Init_Config_s current_PID;
PID_Init_Config_s speed_PID;
PID_Init_Config_s angle_PID;
} Motor_Controller_Init_s;
/* 用于初始化CAN电机的结构体,各类电机通用 */