发射模式手动切换,图传链路通信,UI完善,四个轮子pid分开

This commit is contained in:
zyx 2024-05-04 21:39:54 +08:00
parent d38dd9573d
commit b7905068d7
49 changed files with 12138 additions and 11331 deletions

View File

@ -46,7 +46,7 @@ void MX_USART1_UART_Init(void)
/* USER CODE END USART1_Init 1 */
huart1.Instance = USART1;
huart1.Init.BaudRate = 921600;
huart1.Init.BaudRate = 115200;
huart1.Init.WordLength = UART_WORDLENGTH_8B;
huart1.Init.StopBits = UART_STOPBITS_1;
huart1.Init.Parity = UART_PARITY_NONE;

View File

@ -71,17 +71,17 @@ void ChassisInit() {
.can_init_config.can_handle = &hcan1,
.controller_param_init_config = {
.speed_PID = {
.Kp = 4.25f, // 4.5
.Ki = 0.6f, // 0.6
.Kd = 0.01f, // 0.01
.Kp = 0.0f,
.Ki = 0.0f,
.Kd = 0.0f,
.IntegralLimit = 3000,
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit | PID_Derivative_On_Measurement,
.MaxOut = 30000,
},
.current_PID = {
.Kp = 2.2f, // 2.5
.Ki = 0.6f, // 0.8
.Kd = 0.5f, // 0.2
.Kp = 0.0f,
.Ki = 0.0f,
.Kd = 0.0f,
.IntegralLimit = 3000,
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit | PID_Derivative_On_Measurement,
.MaxOut = 15000,
@ -91,26 +91,39 @@ void ChassisInit() {
.angle_feedback_source = MOTOR_FEED,
.speed_feedback_source = MOTOR_FEED,
.outer_loop_type = SPEED_LOOP,
.close_loop_type = SPEED_LOOP, //| CURRENT_LOOP,
.close_loop_type = SPEED_LOOP, // CURRENT_LOOP,
.power_limit_flag = POWER_LIMIT_ON,
},
.motor_type = M3508,
};
// @todo: 当前还没有设置电机的正反转,仍然需要手动添加reference的正负号,需要电机module的支持,待修改.
// 四个轮子pid分开
chassis_motor_config.can_init_config.tx_id = 1;
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_NORMAL;
chassis_motor_config.controller_param_init_config.speed_PID.Kp = 5.0f;
chassis_motor_config.controller_param_init_config.speed_PID.Ki = 0.01f;
chassis_motor_config.controller_param_init_config.speed_PID.Kd = 0.01f;
motor_rf = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 2;
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_NORMAL;
chassis_motor_config.controller_param_init_config.speed_PID.Kp = 5.1f;
chassis_motor_config.controller_param_init_config.speed_PID.Ki = 0.01f;
chassis_motor_config.controller_param_init_config.speed_PID.Kd = 0.001f;
motor_lf = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 3;
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_NORMAL;
chassis_motor_config.controller_param_init_config.speed_PID.Kp = 5.0f;
chassis_motor_config.controller_param_init_config.speed_PID.Ki = 0.01f;
chassis_motor_config.controller_param_init_config.speed_PID.Kd = 0.01f;
motor_lb = DJIMotorInit(&chassis_motor_config);
chassis_motor_config.can_init_config.tx_id = 4;
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_NORMAL;
chassis_motor_config.controller_param_init_config.speed_PID.Kp = 5.1f;
chassis_motor_config.controller_param_init_config.speed_PID.Ki = 0.01f;
chassis_motor_config.controller_param_init_config.speed_PID.Kd = 0.01f;
motor_rb = DJIMotorInit(&chassis_motor_config);
//超级电容
@ -124,9 +137,9 @@ void ChassisInit() {
power_set = 70;
SuperCapSetPower(cap,power_set); // 超级电容限制功率
//用一阶滤波代替斜波函数生成
first_order_filter_init(&vx_filter, 0.002f, &CHASSIS_ACCEL_X_NUM);
first_order_filter_init(&vy_filter, 0.002f, &CHASSIS_ACCEL_Y_NUM);
//用一阶滤波代替斜波函数生成 //增大更能刹住
first_order_filter_init(&vx_filter, 0.007f, &CHASSIS_ACCEL_X_NUM);
first_order_filter_init(&vy_filter, 0.007f, &CHASSIS_ACCEL_Y_NUM);
// 发布订阅初始化,如果为双板,则需要can comm来传递消息
#ifdef CHASSIS_BOARD
@ -159,13 +172,6 @@ void ChassisInit() {
* @brief ,
* ,
*/
static void MecanumCalculate() {
vt_lf = -chassis_vx - chassis_vy - chassis_cmd_recv.wz * LF_CENTER;
vt_rf = -chassis_vx + chassis_vy - chassis_cmd_recv.wz * RF_CENTER;
vt_lb = chassis_vx - chassis_vy - chassis_cmd_recv.wz * LB_CENTER;
vt_rb = chassis_vx + chassis_vy - chassis_cmd_recv.wz * RB_CENTER;
}
//全向轮解算
static void OmniCalculate() {
vt_rf = -(HALF_TRACK_WIDTH + HALF_WHEEL_BASE) * chassis_cmd_recv.wz + chassis_vx - chassis_vy;
@ -191,7 +197,6 @@ static float EstimatePower(DJIMotorInstance* chassis_motor)
return power;
}
float vofa_send_data[6];
/**
* @brief
*
@ -294,7 +299,6 @@ void ChassisTask() {
chassis_vx = chassis_cmd_recv.vx * cos_theta - chassis_cmd_recv.vy * sin_theta;
chassis_vy = chassis_cmd_recv.vx * sin_theta + chassis_cmd_recv.vy * cos_theta;
// chassis_vx = (1.0f - 0.30f) * chassis_vx + 0.30f * (chassis_cmd_recv.vx * cos_theta - chassis_cmd_recv.vy * sin_theta);
// chassis_vy = (1.0f - 0.30f) * chassis_vy + 0.30f * (chassis_cmd_recv.vx * sin_theta + chassis_cmd_recv.vy * cos_theta);
@ -320,7 +324,7 @@ void ChassisTask() {
//chassis_feedback_data.enemy_color = !referee_data->referee_id.Robot_Color;
// 当前只做了17mm热量的数据获取,后续根据robot_def中的宏切换双枪管和英雄42mm的情况
//chassis_feedback_data.bullet_speed = referee_data->GameRobotState.shooter_id1_17mm_speed_limit;
//chassis_feedback_data.rest_heat = referee_data->PowerHeatData.shooter_heat0;
chassis_feedback_data.cap_power = cap->cap_msg.cap_vol;
// 推送反馈消息

View File

@ -14,6 +14,7 @@
#include "bsp_dwt.h"
#include "bsp_log.h"
#include "referee_task.h"
#include "vision_transfer.h"
// 私有宏,自动将编码器转换成角度值
#define YAW_ALIGN_ANGLE (YAW_CHASSIS_ALIGN_ECD * ECD_ANGLE_COEF_DJI) // 对齐时的角度,0-360
@ -22,6 +23,8 @@
/* cmd应用包含的模块实例指针和交互信息存储*/
#ifdef GIMBAL_BOARD // 对双板的兼容,条件编译
#include "can_comm.h"
#include "user_lib.h"
static CANCommInstance *cmd_can_comm; // 双板通信
#endif
#ifdef ONE_BOARD
@ -33,6 +36,8 @@ static Chassis_Ctrl_Cmd_s chassis_cmd_send; // 发送给底盘应用的信
static Chassis_Upload_Data_s chassis_fetch_data; // 从底盘应用接收的反馈信息信息,底盘功率枪口热量与底盘运动状态等
extern SuperCapInstance *cap; // 超级电容
static RC_ctrl_t *rc_data; // 遥控器数据,初始化时返回
static VT_ctrl_t *vt_data; // 图传链路下发的键鼠遥控数据 与遥控器数据格式保持一致
//static Vision_Recv_s *vision_recv_data; // 视觉接收数据指针,初始化时返回
//static Vision_Send_s vision_send_data; // 视觉发送数据
static RecievePacket_t *vision_recv_data; // 视觉接收数据指针,初始化时返回
@ -52,17 +57,17 @@ static Gimbal_Upload_Data_s gimbal_fetch_data; // 从云台获取的反馈信息
static Publisher_t *shoot_cmd_pub; // 发射控制消息发布者
static Subscriber_t *shoot_feed_sub; // 发射反馈信息订阅者
static Shoot_Ctrl_Cmd_s shoot_cmd_send; // 传递给发射的控制信息
static Shoot_Ctrl_Cmd_s shoot_cmd_recv;
static Shoot_Upload_Data_s shoot_fetch_data; // 从发射获取的反馈信息
static Robot_Status_e robot_state; // 机器人整体工作状态
static referee_info_t *referee_data; // 用于获取裁判系统的数据
static uint8_t load_flag = 0; //拨弹模式选择标志位
void RobotCMDInit() {
rc_data = RemoteControlInit(&huart3); // 修改为对应串口,注意如果是自研板dbus协议串口需选用添加了反相器的那个
vision_recv_data = VisionInit(&huart1); // 视觉通信串口
vision_recv_data = VisionInit(); // 视觉通信串口
vt_data = VTRefereeInit(&huart1); // 图传通信串口
referee_data = UITaskInit(&huart6, &ui_data); // 裁判系统初始化,会同时初始化UI
gimbal_cmd_pub = PubRegister("gimbal_cmd", sizeof(Gimbal_Ctrl_Cmd_s));
@ -117,10 +122,15 @@ static void CalcOffsetAngle() {
#endif
}
/**
* @brief ()
*
*/
//功能:死亡后清除小陀螺的状态
static void death_check()
{
if(referee_data->GameRobotState.current_HP <= 0)
{
rc_data[TEMP].key_count[KEY_PRESS][Key_E] = 0;
}
}
static void update_ui_data() {
ui_data.chassis_mode = chassis_cmd_send.chassis_mode;
ui_data.gimbal_mode = gimbal_cmd_send.gimbal_mode;
@ -128,6 +138,7 @@ static void update_ui_data() {
ui_data.shoot_mode = shoot_cmd_send.shoot_mode;
ui_data.lid_mode = shoot_cmd_send.lid_mode;
ui_data.aim_fire = aim_select.suggest_fire;
ui_data.loader_mode = shoot_cmd_send.loader_mode;
ui_data.Chassis_Power_Data.chassis_power_mx = referee_data->GameRobotState.chassis_power_limit;
ui_data.Chassis_Power_Data.cap_power = chassis_fetch_data.cap_power;
@ -178,6 +189,10 @@ static void auto_aim_mode() {
}
}
/**
* @brief ()
*
*/
static void RemoteControlSet() {
// 控制底盘和云台运行模式,云台待添加,云台是否始终使用IMU数据?
if (switch_is_down(rc_data[TEMP].rc.switch_right)) // 右侧开关状态[下],小陀螺
@ -238,9 +253,9 @@ static void RemoteControlSet() {
// 拨弹控制,遥控器固定为一种拨弹模式,可自行选择
if (rc_data[TEMP].rc.dial < -500)//
shoot_cmd_send.load_mode = LOAD_BURSTFIRE;
shoot_cmd_send.loader_mode = LOAD_BURSTFIRE;
else
shoot_cmd_send.load_mode = LOAD_STOP;
shoot_cmd_send.loader_mode = LOAD_STOP;
// 视觉控制发射
// if (aim_select.suggest_fire == 1) {
@ -253,15 +268,15 @@ static void RemoteControlSet() {
// }
// 射频控制,固定每秒1发,后续可以根据左侧拨轮的值大小切换射频,
shoot_cmd_send.shoot_rate = 8;
shoot_cmd_send.shoot_rate = 18;
if(shoot_fetch_data.stalled_flag ==1)
shoot_cmd_send.load_mode = LOAD_REVERSE;
shoot_cmd_send.loader_mode = LOAD_REVERSE;
}
static void hand_aim_mode() {
// gimbal_cmd_send.yaw += (float) rc_data[TEMP].mouse.x / 660 * 6; // 系数待测
// gimbal_cmd_send.pitch -= (float) rc_data[TEMP].mouse.y / 660 * 6;
}
/**
@ -280,34 +295,37 @@ static void MouseKeySet() {
{
if (shoot_cmd_send.friction_mode == FRICTION_ON) {
shoot_cmd_send.shoot_mode = SHOOT_ON;
shoot_cmd_send.load_mode = LOAD_BURSTFIRE;
if(load_flag == 0){
shoot_cmd_send.loader_mode = LOAD_BURSTFIRE;
}else if(load_flag == 1){
shoot_cmd_send.loader_mode = LOAD_3_BULLET;
}else
shoot_cmd_send.loader_mode = LOAD_1_BULLET;
}
} else if ((!rc_data[TEMP].mouse.press_l) && (!rc_data[TEMP].mouse.press_r))
{
shoot_cmd_send.load_mode = LOAD_STOP;
shoot_cmd_send.loader_mode = LOAD_STOP;
}
if (rc_data[TEMP].mouse.press_r) // 右键自瞄模式
{
if ((vision_recv_data->x == 0 && vision_recv_data->y == 0 && vision_recv_data->z == 0
&& vision_recv_data->vx == 0 && vision_recv_data->vy == 0 &&
vision_recv_data->vz == 0))
{
shoot_cmd_send.load_mode = LOAD_STOP;
shoot_cmd_send.loader_mode = LOAD_STOP;
} else {
auto_aim_mode();
if (aim_select.suggest_fire == 1 && rc_data[TEMP].mouse.press_l &&
shoot_cmd_send.friction_mode == FRICTION_ON) {
shoot_cmd_send.shoot_mode = SHOOT_ON;
shoot_cmd_send.load_mode = LOAD_BURSTFIRE;
shoot_cmd_send.loader_mode = LOAD_BURSTFIRE;
} else {
shoot_cmd_send.load_mode = LOAD_STOP;
shoot_cmd_send.loader_mode = LOAD_STOP;
}
}
}
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_R] % 2) // R键手动刷新UI
{
case 1:
@ -329,7 +347,7 @@ static void MouseKeySet() {
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_F] % 2) // F键开关摩擦轮
{
case 0:
// shoot_cmd_send.shoot_mode = SHOOT_OFF;
shoot_cmd_send.shoot_mode = SHOOT_OFF;
shoot_cmd_send.friction_mode = FRICTION_OFF;
break;
default:
@ -357,7 +375,18 @@ static void MouseKeySet() {
gimbal_cmd_send.gimbal_mode = GIMBAL_GYRO_MODE;
break;
}
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_G] % 3) // G键切换发射模式
{
case 0:
load_flag = 0;
break;
case 1:
load_flag = 1;
break;
default:
load_flag = 3;
break;
}
switch (rc_data[TEMP].key[KEY_PRESS].shift) //按shift允许消耗超级电容能量
{
case 0:
@ -368,12 +397,137 @@ static void MouseKeySet() {
break;
}
shoot_cmd_send.shoot_rate = 25;//8
shoot_cmd_send.shoot_rate = 25;
if(shoot_fetch_data.stalled_flag ==1)
shoot_cmd_send.load_mode = LOAD_REVERSE;
shoot_cmd_send.loader_mode = LOAD_REVERSE;
death_check();
}
/**
* @brief
*
*/
static void VTMouseKeySet()
{
chassis_cmd_send.vy = vt_data[TEMP].key[KEY_PRESS].w * 3000 - vt_data[TEMP].key[KEY_PRESS].s * 3000; // 系数待测
chassis_cmd_send.vx = vt_data[TEMP].key[KEY_PRESS].a * 3000 - vt_data[TEMP].key[KEY_PRESS].d * 3000;
gimbal_cmd_send.yaw -= (float) vt_data[TEMP].mouse.x / 660 * 4; // 系数待测
gimbal_cmd_send.pitch += (float) vt_data[TEMP].mouse.y / 660 * 6;
aim_select.suggest_fire = 0;
if (vt_data[TEMP].mouse.press_l && (!vt_data[TEMP].mouse.press_r)) // 左键发射模式
{
if (shoot_cmd_send.friction_mode == FRICTION_ON) {
shoot_cmd_send.shoot_mode = SHOOT_ON;
shoot_cmd_send.loader_mode = LOAD_BURSTFIRE;
}
} else if ((!vt_data[TEMP].mouse.press_l) && (!vt_data[TEMP].mouse.press_r))
{
shoot_cmd_send.loader_mode = LOAD_STOP;
}
if (vt_data[TEMP].mouse.press_r) // 右键自瞄模式
{
if ((vision_recv_data->x == 0 && vision_recv_data->y == 0 && vision_recv_data->z == 0
&& vision_recv_data->vx == 0 && vision_recv_data->vy == 0 &&
vision_recv_data->vz == 0))
{
shoot_cmd_send.loader_mode = LOAD_STOP;
} else {
auto_aim_mode();
if (aim_select.suggest_fire == 1 && vt_data[TEMP].mouse.press_l &&
shoot_cmd_send.friction_mode == FRICTION_ON) {
shoot_cmd_send.shoot_mode = SHOOT_ON;
shoot_cmd_send.loader_mode = LOAD_BURSTFIRE;
} else {
shoot_cmd_send.loader_mode = LOAD_STOP;
}
}
}
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_R] % 2) // R键手动刷新UI
{
case 1:
MyUIInit();
vt_data[TEMP].key_count[KEY_PRESS][Key_R]++;
break;
default:
break;
}
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_V] % 2) // V键开关红点激光
{
case 0:
HAL_GPIO_WritePin(GPIOC,GPIO_PIN_8,GPIO_PIN_SET);
break;
default:
HAL_GPIO_WritePin(GPIOC,GPIO_PIN_8,GPIO_PIN_RESET);
break;
}
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_F] % 2) // F键开关摩擦轮
{
case 0:
shoot_cmd_send.shoot_mode = SHOOT_OFF;
shoot_cmd_send.friction_mode = FRICTION_OFF;
break;
default:
shoot_cmd_send.shoot_mode = SHOOT_ON;
shoot_cmd_send.friction_mode = FRICTION_ON;
break;
}
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_Q] % 2) // Q键开关弹舱盖
{
case 0:
shoot_cmd_send.lid_mode = LID_OPEN;
break;
default:
shoot_cmd_send.lid_mode = LID_CLOSE;
break;
}
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_E] % 2) // E键开关小陀螺
{
case 0:
chassis_cmd_send.chassis_mode = CHASSIS_FOLLOW_GIMBAL_YAW;
gimbal_cmd_send.gimbal_mode = GIMBAL_FREE_MODE;
break;
default:
chassis_cmd_send.chassis_mode = CHASSIS_ROTATE;
gimbal_cmd_send.gimbal_mode = GIMBAL_GYRO_MODE;
break;
}
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_G] % 3) // G键切换发射模式
{
case 0:
load_flag = 0;
break;
case 1:
load_flag = 1;
break;
default:
load_flag = 3;
break;
}
switch (vt_data[TEMP].key[KEY_PRESS].shift) //按shift允许消耗超级电容能量
{
case 0:
SuperCapSetPower(cap,40);
break;
default:
SuperCapSetPower(cap,70);
break;
}
shoot_cmd_send.shoot_rate = 25;
if(shoot_fetch_data.stalled_flag ==1)
shoot_cmd_send.loader_mode = LOAD_REVERSE;
death_check();
}
/**
* @brief ,/线/
* '300',.
@ -390,7 +544,7 @@ static void EmergencyHandler() {
chassis_cmd_send.chassis_mode = CHASSIS_ZERO_FORCE;
shoot_cmd_send.shoot_mode = SHOOT_OFF;
shoot_cmd_send.friction_mode = FRICTION_OFF;
shoot_cmd_send.load_mode = LOAD_STOP;
shoot_cmd_send.loader_mode = LOAD_STOP;
LOGERROR("[CMD] emergency stop!");
}
// 遥控器右侧开关为[上],恢复正常运行
@ -419,8 +573,12 @@ void RobotCMDTask() {
if (switch_is_down(rc_data[TEMP].rc.switch_left) ||
switch_is_mid(rc_data[TEMP].rc.switch_left)) // 遥控器左侧开关状态为[下],[中],遥控器控制
RemoteControlSet();
else if (switch_is_up(rc_data[TEMP].rc.switch_left)) // 遥控器左侧开关状态为[上],键盘控制
else if (switch_is_up(rc_data[TEMP].rc.switch_left) &&
switch_is_mid(rc_data[TEMP].rc.switch_right)) // 遥控器左侧开关状态为[上],键盘控制,遥控器右侧开关状态为[中],遥控器通道
MouseKeySet();
else if (switch_is_up(rc_data[TEMP].rc.switch_left) &&
switch_is_up(rc_data[TEMP].rc.switch_right)) // 遥控器左侧开关状态为[上],键盘控制,遥控器右侧开关状态为[上],图传链路通道
VTMouseKeySet();
EmergencyHandler(); // 处理模块离线和遥控器急停等紧急情况
@ -431,6 +589,10 @@ void RobotCMDTask() {
chassis_cmd_send.chassis_power_limit = referee_data->GameRobotState.chassis_power_limit;
//根据裁判系统反馈确定缓冲功率
chassis_cmd_send.buffer_energy = referee_data->PowerHeatData.buffer_energy;
//根据裁判系统反馈确定枪管热量控制
shoot_cmd_send.heat = referee_data->PowerHeatData.shooter_17mm_1_barrel_heat;
shoot_cmd_send.heat_limit = referee_data->GameRobotState.shooter_barrel_heat_limit;
shoot_cmd_send.heat_cool = referee_data->GameRobotState.shooter_barrel_cooling_value;
// 推送消息,双板通信,视觉通信等
// 其他应用所需的控制数据在remotecontrolsetmode和mousekeysetmode中完成设置

View File

@ -1,5 +1,6 @@
#ifndef ROBOT_CMD_H
#define ROBOT_CMD_H
#include "remote_control.h"
/**

View File

@ -26,7 +26,7 @@
/* 机器人重要参数定义,注意根据不同机器人进行修改,浮点数需要以.0或f结尾,无符号以u结尾 */
// 云台参数
#define YAW_CHASSIS_ALIGN_ECD 1371 // 云台和底盘对齐指向相同方向时的电机编码器值,若对云台有机械改动需要修改
#define YAW_CHASSIS_ALIGN_ECD 1443 // 云台和底盘对齐指向相同方向时的电机编码器值,若对云台有机械改动需要修改
#define YAW_ECD_GREATER_THAN_4096 0 // ALIGN_ECD值是否大于4096,是为1,否为0;用于计算云台偏转角度
#define PITCH_HORIZON_ECD 4422 // 云台处于水平位置时编码器值,若对云台有机械改动需要修改
#define PITCH_MAX_ANGLE 18 // 云台竖直方向最大角度 (注意反馈如果是陀螺仪,则填写陀螺仪的角度)
@ -35,10 +35,9 @@
#define PITCH_MAX_RELATIVE_ANGLE 123 // 云台相对底盘最大角度
#define PITCH_MIN_RELATIVE_ANGLE 80 // 云台相对底盘最小角度
// 发射参数
#define ONE_BULLET_DELTA_ANGLE 45 // 发射一发弹丸拨盘转动的距离,由机械设计图纸给出
#define REDUCTION_RATIO_LOADER 49.0f // 拨盘电机的减速比,英雄需要修改为3508的19.0f
#define ONE_BULLET_DELTA_ANGLE 1620 // 发射一发弹丸拨盘转动的距离,由机械设计图纸给出
#define REDUCTION_RATIO_LOADER 36.0f // 拨盘电机的减速比,英雄需要修改为3508的19.0f 2006-36.0f
#define NUM_PER_CIRCLE 8 // 拨盘一圈的装载量
// 机器人底盘修改的参数,单位为m(米)
#define WHEEL_BASE 0.1f // 纵向轴距(前进后退方向)
@ -172,12 +171,15 @@ typedef struct
typedef struct
{
shoot_mode_e shoot_mode;
loader_mode_e load_mode;
loader_mode_e loader_mode;
lid_mode_e lid_mode;
friction_mode_e friction_mode;
Bullet_Speed_e bullet_speed; // 弹速枚举
uint8_t rest_heat;
float shoot_rate; // 连续发射的射频,unit per s,发/秒
uint16_t heat; // 实时热量
uint16_t heat_limit; // 热量上限
uint16_t heat_cool; // 热量每秒冷却值
} Shoot_Ctrl_Cmd_s;
/* ----------------gimbal/shoot/chassis发布的反馈数据----------------*/
@ -196,7 +198,6 @@ typedef struct
// float real_vy;
// float real_wz;
uint8_t rest_heat; // 剩余枪口热量
Bullet_Speed_e bullet_speed; // 弹速限制
Enemy_Color_e enemy_color; // 0 for red, 1 for blue
uint16_t chassis_power_mx;

View File

@ -68,10 +68,10 @@ void ShootInit()
.controller_param_init_config = {
.angle_PID = {
// 如果启用位置环来控制发弹,需要较大的I值保证输出力矩的线性度否则出现接近拨出的力矩大幅下降
.Kp = 0, // 10
.Ki = 0,
.Kp = 500,
.Ki = 100,
.Kd = 0,
.MaxOut = 200,
.MaxOut = 5000,
},
.speed_PID = {
.Kp = 2, // 3
@ -91,10 +91,12 @@ void ShootInit()
},
},
.controller_setting_init_config = {
.angle_feedback_source = MOTOR_FEED, .speed_feedback_source = MOTOR_FEED,
.angle_feedback_source = MOTOR_FEED,
.speed_feedback_source = MOTOR_FEED,
.outer_loop_type = SPEED_LOOP, // 初始化成SPEED_LOOP,让拨盘停在原地,防止拨盘上电时乱转
.close_loop_type = CURRENT_LOOP | SPEED_LOOP,
.motor_reverse_flag = MOTOR_DIRECTION_REVERSE, // 注意方向设置为拨盘的拨出的击发方向
.close_loop_type = SPEED_LOOP | ANGLE_LOOP,
.motor_reverse_flag = MOTOR_DIRECTION_NORMAL, // 注意方向设置为拨盘的拨出的击发方向
//.feedback_reverse_flag = FEEDBACK_DIRECTION_REVERSE,
},
.motor_type = M2006 // 英雄使用m3508
};
@ -121,6 +123,7 @@ void ShootInit()
// .id = 1;
// }
}
//卡弹检测
void stalled_detect()
{
@ -135,7 +138,7 @@ void stalled_detect()
return;
// reference_angle = (detect_time - last_detect_time) * loader->motor_controller.speed_PID.Ref * 1e-3f;
// real_angle = loader->measure.total_angle - last_total_angle;
if(shoot_cmd_recv.load_mode == LOAD_BURSTFIRE)
if(shoot_cmd_recv.loader_mode == LOAD_BURSTFIRE)
{
//if(real_angle < reference_angle * 0.2f)
if(abs(loader->measure.real_current)>=9500)
@ -150,6 +153,18 @@ void stalled_detect()
// last_total_angle = loader->measure.total_angle;
}
// 热量控制
void Heat_control()
{
if(shoot_cmd_recv.heat>=(0.9*shoot_cmd_recv.heat_limit))
{
DJIMotorStop(loader);
}
else
{
DJIMotorEnable(loader);
}
}
/* 机器人发射机构控制核心任务 */
void ShootTask()
@ -160,8 +175,8 @@ void ShootTask()
// 对shoot mode等于SHOOT_STOP的情况特殊处理,直接停止所有电机(紧急停止)
if (shoot_cmd_recv.shoot_mode == SHOOT_OFF)
{
DJIMotorStop(friction_l);
DJIMotorStop(friction_r);
DJIMotorSetRef(friction_l, 0);
DJIMotorSetRef(friction_r, 0);
DJIMotorStop(loader);
}
else // 恢复运行
@ -170,13 +185,6 @@ void ShootTask()
DJIMotorEnable(friction_r);
DJIMotorEnable(loader);
}
//单独测试波胆
// DJIMotorEnable(loader);
//
// shoot_cmd_recv.load_mode = LOAD_BURSTFIRE;
// shoot_cmd_recv.shoot_rate = 20;
// if(shoot_feedback_data.stalled_flag ==1)
// shoot_cmd_recv.load_mode = LOAD_REVERSE;
// 如果上一次触发单发或3发指令的时间加上不应期仍然大于当前时间(尚未休眠完毕),直接返回即可
// 单发模式主要提供给能量机关激活使用(以及英雄的射击大部分处于单发)
@ -184,7 +192,7 @@ void ShootTask()
return;
// 若不在休眠状态,根据robotCMD传来的控制模式进行拨盘电机参考值设定和模式切换
switch (shoot_cmd_recv.load_mode)
switch (shoot_cmd_recv.loader_mode)
{
// 停止拨盘
case LOAD_STOP:
@ -193,22 +201,22 @@ void ShootTask()
break;
// 单发模式,根据鼠标按下的时间,触发一次之后需要进入不响应输入的状态(否则按下的时间内可能多次进入,导致多次发射)
case LOAD_1_BULLET: // 激活能量机关/干扰对方用,英雄用.
DJIMotorOuterLoop(loader, ANGLE_LOOP); // 切换到角度环
DJIMotorSetRef(loader, loader->measure.total_angle + ONE_BULLET_DELTA_ANGLE); // 控制量增加一发弹丸的角度
DJIMotorOuterLoop(loader, ANGLE_LOOP); // 切换到角度环
DJIMotorSetRef(loader, loader->measure.total_angle - ONE_BULLET_DELTA_ANGLE); // 控制量增加一发弹丸的角度
hibernate_time = DWT_GetTimeline_ms(); // 记录触发指令的时间
dead_time = 150; // 完成1发弹丸发射的时间
break;
// 三连发,如果不需要后续可能删除
case LOAD_3_BULLET:
DJIMotorOuterLoop(loader, ANGLE_LOOP); // 切换到速度环
DJIMotorSetRef(loader, loader->measure.total_angle + 3 * ONE_BULLET_DELTA_ANGLE); // 增加3发
DJIMotorOuterLoop(loader, ANGLE_LOOP); // 切换到角度环
DJIMotorSetRef(loader, loader->measure.total_angle - 3 * ONE_BULLET_DELTA_ANGLE); // 增加3发
hibernate_time = DWT_GetTimeline_ms(); // 记录触发指令的时间
dead_time = 300; // 完成3发弹丸发射的时间
dead_time = 1000; // 完成3发弹丸发射的时间
break;
// 连发模式,对速度闭环,射频后续修改为可变,目前固定为1Hz
case LOAD_BURSTFIRE:
DJIMotorOuterLoop(loader, SPEED_LOOP);
DJIMotorSetRef(loader, shoot_cmd_recv.shoot_rate * 360 * REDUCTION_RATIO_LOADER / 8);
DJIMotorSetRef(loader, -(shoot_cmd_recv.shoot_rate * 360 * REDUCTION_RATIO_LOADER / 8));
// x颗/秒换算成速度: 已知一圈的载弹量,由此计算出1s需要转的角度,注意换算角速度(DJIMotor的速度单位是angle per second)
break;
@ -216,7 +224,7 @@ void ShootTask()
// 也有可能需要从switch-case中独立出来
case LOAD_REVERSE:
DJIMotorOuterLoop(loader, SPEED_LOOP);
DJIMotorSetRef(loader, -8 * 360 * REDUCTION_RATIO_LOADER / 8); // 固定速度反转
DJIMotorSetRef(loader, 8 * 360 * REDUCTION_RATIO_LOADER / 8); // 固定速度反转
hibernate_time = DWT_GetTimeline_ms(); // 记录触发指令的时间
dead_time = 100; // 翻转500ms
shoot_feedback_data.stalled_flag = 0 ; //清除堵转标志
@ -261,7 +269,6 @@ void ShootTask()
if (shoot_cmd_recv.lid_mode == LID_CLOSE)
{
Servo_Motor_FreeAngle_Set(lid,95);
//...
}
else if (shoot_cmd_recv.lid_mode == LID_OPEN)
{
@ -269,12 +276,8 @@ void ShootTask()
}
//卡弹检测
stalled_detect();
// DJIMotorEnable(friction_l);
// DJIMotorEnable(friction_r);
// DJIMotorSetRef(friction_l, 30000);
// DJIMotorSetRef(friction_r, 30000);
// 热量控制
Heat_control();
// 反馈数据,目前暂时没有要设定的反馈数据,后续可能增加应用离线监测以及卡弹反馈
PubPushMessage(shoot_pub, (void *)&shoot_feedback_data);

View File

@ -58,8 +58,8 @@ CMAKE_CODEBLOCKS_MAKE_ARGUMENTS:STRING=
//Enable colored diagnostics throughout.
CMAKE_COLOR_DIAGNOSTICS:BOOL=ON
//CXX compiler
CMAKE_CXX_COMPILER:STRING=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-g++.exe
//No help, variable specified on the command line.
CMAKE_CXX_COMPILER:UNINITIALIZED=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-g++.exe
//A wrapper around 'ar' adding the appropriate '--plugin' option
// for the GCC compiler
@ -84,8 +84,8 @@ CMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG
//Flags used by the CXX compiler during RELWITHDEBINFO builds.
CMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
//C compiler
CMAKE_C_COMPILER:STRING=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe
//No help, variable specified on the command line.
CMAKE_C_COMPILER:UNINITIALIZED=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe
//A wrapper around 'ar' adding the appropriate '--plugin' option
// for the GCC compiler

View File

@ -7,98 +7,22 @@ set(CMAKE_DEPENDS_GENERATOR "MinGW Makefiles")
# The top level Makefile was generated from the following files:
set(CMAKE_MAKEFILE_DEPENDS
"CMakeCache.txt"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeASMCompiler.cmake.in"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeASMInformation.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCCompiler.cmake.in"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCCompilerABI.c"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCInformation.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCXXCompiler.cmake.in"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCXXCompilerABI.cpp"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCXXInformation.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCommonLanguageInclude.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeCompilerIdDetection.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineASMCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCXXCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCompileFeatures.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCompilerABI.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineCompilerId.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeDetermineSystem.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeExtraGeneratorDetermineCompilerMacrosAndIncludeDirs.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeFindBinUtils.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeFindCodeBlocks.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeGenericSystem.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeInitializeConfigs.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeLanguageInformation.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeParseImplicitIncludeInfo.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeParseImplicitLinkInfo.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeParseLibraryArchitecture.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeSystem.cmake.in"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeSystemSpecificInformation.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeSystemSpecificInitialize.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeTestASMCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeTestCCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeTestCXXCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/CMakeTestCompilerCommon.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/ADSP-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/ARMCC-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/ARMClang-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/AppleClang-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Borland-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Bruce-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/CMakeCommonCompilerMacros.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Clang-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Clang-DetermineCompilerInternal.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Comeau-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Compaq-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Compaq-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Cray-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Embarcadero-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Fujitsu-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/FujitsuClang-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GHS-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-ASM.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-C.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-CXX.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU-FindBinUtils.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/GNU.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/HP-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/HP-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IAR-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IBMCPP-C-DetermineVersionInternal.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IBMCPP-CXX-DetermineVersionInternal.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IBMClang-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IBMClang-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Intel-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/IntelLLVM-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/LCC-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/LCC-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/MSVC-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/NVHPC-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/NVIDIA-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/OpenWatcom-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/PGI-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/PathScale-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/SCO-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/SDCC-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/SunPro-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/SunPro-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/TI-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Tasking-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/TinyCC-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/VisualAge-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/VisualAge-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/Watcom-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/XL-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/XL-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/XLClang-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/XLClang-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/zOS-C-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Compiler/zOS-CXX-DetermineCompiler.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Internal/FeatureTesting.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/Platform/Generic.cmake"
"D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26/Modules/ProcessorCount.cmake"
"D:/zhandui/cqdm/bubing_9/CMakeLists.txt"
@ -116,12 +40,6 @@ set(CMAKE_MAKEFILE_OUTPUTS
# Byproducts of CMake generate step:
set(CMAKE_MAKEFILE_PRODUCTS
"CMakeFiles/3.26.4/CMakeSystem.cmake"
"CMakeFiles/3.26.4/CMakeCCompiler.cmake"
"CMakeFiles/3.26.4/CMakeCXXCompiler.cmake"
"CMakeFiles/3.26.4/CMakeASMCompiler.cmake"
"CMakeFiles/3.26.4/CMakeCCompiler.cmake"
"CMakeFiles/3.26.4/CMakeCXXCompiler.cmake"
"CMakeFiles/CMakeDirectoryInformation.cmake"
)

View File

@ -208,6 +208,7 @@ set(CMAKE_DEPENDS_DEPENDENCY_FILES
"D:/zhandui/cqdm/bubing_9/modules/referee/referee_UI.c" "CMakeFiles/basic_framework.elf.dir/modules/referee/referee_UI.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/referee/referee_UI.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/referee/referee_task.c" "CMakeFiles/basic_framework.elf.dir/modules/referee/referee_task.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/referee/referee_task.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/referee/rm_referee.c" "CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c" "CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.c" "CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/standard_cmd/std_cmd.c" "CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj.d"
"D:/zhandui/cqdm/bubing_9/modules/super_cap/super_cap.c" "CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj" "gcc" "CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj.d"

View File

@ -123,4 +123,5 @@ CMakeFiles/basic_framework.elf.dir/application/cmd/robot_cmd.c.obj: \
D:\zhandui\cqdm\bubing_9\Middlewares\Third_Party\FreeRTOS\Source\include/portable.h \
D:\zhandui\cqdm\bubing_9\Middlewares\Third_Party\FreeRTOS\Source\include/deprecated_definitions.h \
D:\zhandui\cqdm\bubing_9\Middlewares\Third_Party\FreeRTOS\Source\portable\GCC\ARM_CM4F/portmacro.h \
D:\zhandui\cqdm\bubing_9\Middlewares\Third_Party\FreeRTOS\Source\include/mpu_wrappers.h
D:\zhandui\cqdm\bubing_9\Middlewares\Third_Party\FreeRTOS\Source\include/mpu_wrappers.h \
D:\zhandui\cqdm\bubing_9\modules\referee/vision_transfer.h

View File

@ -154,4 +154,5 @@ CMakeFiles/basic_framework.elf.dir/application/robot.c.obj: \
D:\zhandui\cqdm\bubing_9\application\chassis/chassis.h \
D:\zhandui\cqdm\bubing_9\application\gimbal/gimbal.h \
D:\zhandui\cqdm\bubing_9\application\shoot/shoot.h \
D:\zhandui\cqdm\bubing_9\application\cmd/robot_cmd.h
D:\zhandui\cqdm\bubing_9\application\cmd/robot_cmd.h \
D:\zhandui\cqdm\bubing_9\modules\remote/remote_control.h

View File

@ -1788,10 +1788,24 @@ CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling C source to assembly CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.s"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -S D:\zhandui\cqdm\bubing_9\modules\referee\rm_referee.c -o CMakeFiles\basic_framework.elf.dir\modules\referee\rm_referee.c.s
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj: D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_124) "Building C object CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\referee\vision_transfer.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\referee\vision_transfer.c.obj -c D:\zhandui\cqdm\bubing_9\modules\referee\vision_transfer.c
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.i: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Preprocessing C source to CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.i"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -E D:\zhandui\cqdm\bubing_9\modules\referee\vision_transfer.c > CMakeFiles\basic_framework.elf.dir\modules\referee\vision_transfer.c.i
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.s: cmake_force
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green "Compiling C source to assembly CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.s"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -S D:\zhandui\cqdm\bubing_9\modules\referee\vision_transfer.c -o CMakeFiles\basic_framework.elf.dir\modules\referee\vision_transfer.c.s
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj: D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.c
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_124) "Building C object CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_125) "Building C object CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\remote\remote_control.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\remote\remote_control.c.obj -c D:\zhandui\cqdm\bubing_9\modules\remote\remote_control.c
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.i: cmake_force
@ -1805,7 +1819,7 @@ CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.s: cmake_forc
CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj: D:/zhandui/cqdm/bubing_9/modules/standard_cmd/std_cmd.c
CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_125) "Building C object CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_126) "Building C object CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\standard_cmd\std_cmd.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\standard_cmd\std_cmd.c.obj -c D:\zhandui\cqdm\bubing_9\modules\standard_cmd\std_cmd.c
CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.i: cmake_force
@ -1819,7 +1833,7 @@ CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.s: cmake_force
CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj: D:/zhandui/cqdm/bubing_9/modules/super_cap/super_cap.c
CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_126) "Building C object CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_127) "Building C object CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\super_cap\super_cap.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\super_cap\super_cap.c.obj -c D:\zhandui\cqdm\bubing_9\modules\super_cap\super_cap.c
CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.i: cmake_force
@ -1833,7 +1847,7 @@ CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.s: cmake_force
CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj: D:/zhandui/cqdm/bubing_9/modules/unicomm/unicomm.c
CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_127) "Building C object CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_128) "Building C object CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\unicomm\unicomm.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\unicomm\unicomm.c.obj -c D:\zhandui\cqdm\bubing_9\modules\unicomm\unicomm.c
CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.i: cmake_force
@ -1847,7 +1861,7 @@ CMakeFiles/basic_framework.elf.dir/modules/unicomm/unicomm.c.s: cmake_force
CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj: CMakeFiles/basic_framework.elf.dir/flags.make
CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj: D:/zhandui/cqdm/bubing_9/modules/vofa/vofa.c
CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj: CMakeFiles/basic_framework.elf.dir/compiler_depend.ts
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_128) "Building C object CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_129) "Building C object CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj"
D:\gcc-arm-none-eabi-10.3-2021.10-win32\gcc-arm-none-eabi-10.3-2021.10\bin\arm-none-eabi-gcc.exe $(C_DEFINES) $(C_INCLUDES) $(C_FLAGS) -MD -MT CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.obj -MF CMakeFiles\basic_framework.elf.dir\modules\vofa\vofa.c.obj.d -o CMakeFiles\basic_framework.elf.dir\modules\vofa\vofa.c.obj -c D:\zhandui\cqdm\bubing_9\modules\vofa\vofa.c
CMakeFiles/basic_framework.elf.dir/modules/vofa/vofa.c.i: cmake_force
@ -1983,6 +1997,7 @@ basic_framework_elf_OBJECTS = \
"CMakeFiles/basic_framework.elf.dir/modules/referee/referee_UI.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/referee/referee_task.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj" \
"CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj" \
@ -2115,6 +2130,7 @@ basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/referee/crc_ref.
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/referee/referee_UI.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/referee/referee_task.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/modules/super_cap/super_cap.c.obj
@ -2124,7 +2140,7 @@ basic_framework.elf: CMakeFiles/basic_framework.elf.dir/build.make
basic_framework.elf: D:/zhandui/cqdm/bubing_9/Middlewares/ST/ARM/DSP/Lib/libarm_cortexM4lf_math.a
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/objects1.rsp
basic_framework.elf: CMakeFiles/basic_framework.elf.dir/link.txt
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_129) "Linking C executable basic_framework.elf"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green --bold --progress-dir=D:\zhandui\cqdm\bubing_9\cmake-build-debug\CMakeFiles --progress-num=$(CMAKE_PROGRESS_130) "Linking C executable basic_framework.elf"
$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles\basic_framework.elf.dir\link.txt --verbose=$(VERBOSE)
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --blue --bold "Building D:/zhandui/cqdm/bubing_9/cmake-build-debug/basic_framework.hex"
@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --blue --bold "Building D:/zhandui/cqdm/bubing_9/cmake-build-debug/basic_framework.bin"

View File

@ -243,6 +243,8 @@ file(REMOVE_RECURSE
"CMakeFiles/basic_framework.elf.dir/modules/referee/referee_task.c.obj.d"
"CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj"
"CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj.d"
"CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj"
"CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj.d"
"CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj"
"CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj.d"
"CMakeFiles/basic_framework.elf.dir/modules/standard_cmd/std_cmd.c.obj"

View File

@ -4294,6 +4294,7 @@ CMakeFiles/basic_framework.elf.dir/application/cmd/robot_cmd.c.obj
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/deprecated_definitions.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/mpu_wrappers.h
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h
CMakeFiles/basic_framework.elf.dir/application/gimbal/gimbal.c.obj
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.c
@ -4576,6 +4577,7 @@ CMakeFiles/basic_framework.elf.dir/application/robot.c.obj
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.h
D:/zhandui/cqdm/bubing_9/application/shoot/shoot.h
D:/zhandui/cqdm/bubing_9/application/cmd/robot_cmd.h
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h
CMakeFiles/basic_framework.elf.dir/application/shoot/shoot.c.obj
D:/zhandui/cqdm/bubing_9/application/shoot/shoot.c
@ -8356,6 +8358,132 @@ CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/event_groups.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h
D:/zhandui/cqdm/bubing_9/Inc/usart.h
D:/zhandui/cqdm/bubing_9/Inc/main.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h
D:/zhandui/cqdm/bubing_9/Inc/stm32f4xx_hal_conf.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/core_cm4.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stdint.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdint.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_default_types.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/features.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_newlib_version.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_intsup.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_stdint.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_version.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_compiler.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_gcc.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/mpu_armv7.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stddef.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h
D:/zhandui/cqdm/bubing_9/modules/referee/referee_protocol.h
D:/zhandui/cqdm/bubing_9/application/robot_def.h
D:/zhandui/cqdm/bubing_9/modules/imu/ins_task.h
D:/zhandui/cqdm/bubing_9/modules/imu/BMI088driver.h
D:/zhandui/cqdm/bubing_9/Inc/main.h
D:/zhandui/cqdm/bubing_9/modules/algorithm/QuaternionEKF.h
D:/zhandui/cqdm/bubing_9/modules/algorithm/kalman_filter.h
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h
D:/zhandui/cqdm/bubing_9/Middlewares/ST/ARM/DSP/Inc/arm_math.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/string.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_ansi.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/newlib.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/config.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/ieeefp.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/reent.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_ansi.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_types.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_types.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/lock.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/cdefs.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_locale.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/strings.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/string.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/math.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdlib.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/stdlib.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/alloca.h
D:/zhandui/cqdm/bubing_9/modules/master_machine/master_process.h
D:/zhandui/cqdm/bubing_9/bsp/usart/bsp_usart.h
D:/zhandui/cqdm/bubing_9/modules/master_machine/seasky_protocol.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdio.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stdarg.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/types.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/endian.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_endian.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/select.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_sigset.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_timeval.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/timespec.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_timespec.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_pthreadtypes.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/sched.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/types.h
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/stdio.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/FreeRTOS.h
D:/zhandui/cqdm/bubing_9/Inc/FreeRTOSConfig.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/projdefs.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/portable.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/deprecated_definitions.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/mpu_wrappers.h
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h
D:/zhandui/cqdm/bubing_9/modules/referee/crc_ref.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/task.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/list.h
D:/zhandui/cqdm/bubing_9/modules/daemon/daemon.h
D:/zhandui/cqdm/bubing_9/bsp/log/bsp_log.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/RTT/SEGGER_RTT.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/Config/SEGGER_RTT_Conf.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/Config/SEGGER_RTT_Conf.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/task.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/queue.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/semphr.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/queue.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/event_groups.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.c
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h

View File

@ -4219,7 +4219,8 @@ CMakeFiles/basic_framework.elf.dir/application/cmd/robot_cmd.c.obj: D:/zhandui/c
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/portable.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/deprecated_definitions.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/mpu_wrappers.h
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/mpu_wrappers.h \
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h
CMakeFiles/basic_framework.elf.dir/application/gimbal/gimbal.c.obj: D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.c \
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.h \
@ -4499,7 +4500,8 @@ CMakeFiles/basic_framework.elf.dir/application/robot.c.obj: D:/zhandui/cqdm/bubi
D:/zhandui/cqdm/bubing_9/application/chassis/chassis.h \
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.h \
D:/zhandui/cqdm/bubing_9/application/shoot/shoot.h \
D:/zhandui/cqdm/bubing_9/application/cmd/robot_cmd.h
D:/zhandui/cqdm/bubing_9/application/cmd/robot_cmd.h \
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h
CMakeFiles/basic_framework.elf.dir/application/shoot/shoot.c.obj: D:/zhandui/cqdm/bubing_9/application/shoot/shoot.c \
D:/zhandui/cqdm/bubing_9/application/shoot/shoot.h \
@ -8235,6 +8237,131 @@ CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.obj: D:/zhandui/
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/event_groups.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h
CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj: D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c \
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h \
D:/zhandui/cqdm/bubing_9/Inc/usart.h \
D:/zhandui/cqdm/bubing_9/Inc/main.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h \
D:/zhandui/cqdm/bubing_9/Inc/stm32f4xx_hal_conf.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/core_cm4.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stdint.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdint.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_default_types.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/features.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_newlib_version.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_intsup.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_stdint.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_version.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_compiler.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/cmsis_gcc.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Include/mpu_armv7.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/system_stm32f4xx.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stddef.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h \
D:/zhandui/cqdm/bubing_9/Drivers/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h \
D:/zhandui/cqdm/bubing_9/modules/referee/referee_protocol.h \
D:/zhandui/cqdm/bubing_9/application/robot_def.h \
D:/zhandui/cqdm/bubing_9/modules/imu/ins_task.h \
D:/zhandui/cqdm/bubing_9/modules/imu/BMI088driver.h \
D:/zhandui/cqdm/bubing_9/Inc/main.h \
D:/zhandui/cqdm/bubing_9/modules/algorithm/QuaternionEKF.h \
D:/zhandui/cqdm/bubing_9/modules/algorithm/kalman_filter.h \
D:/zhandui/cqdm/bubing_9/Drivers/CMSIS/Device/ST/STM32F4xx/Include/stm32f407xx.h \
D:/zhandui/cqdm/bubing_9/Middlewares/ST/ARM/DSP/Inc/arm_math.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/string.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_ansi.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/newlib.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/config.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/ieeefp.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/reent.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/_ansi.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_types.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_types.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/lock.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/cdefs.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_locale.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/strings.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/string.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/math.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdlib.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/stdlib.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/alloca.h \
D:/zhandui/cqdm/bubing_9/modules/master_machine/master_process.h \
D:/zhandui/cqdm/bubing_9/bsp/usart/bsp_usart.h \
D:/zhandui/cqdm/bubing_9/modules/master_machine/seasky_protocol.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/stdio.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stdarg.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/types.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/endian.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/_endian.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/select.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_sigset.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_timeval.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/timespec.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_timespec.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/_pthreadtypes.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/sched.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/machine/types.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/arm-none-eabi/include/sys/stdio.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/FreeRTOS.h \
D:/zhandui/cqdm/bubing_9/Inc/FreeRTOSConfig.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/projdefs.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/portable.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/deprecated_definitions.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/portable/GCC/ARM_CM4F/portmacro.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/mpu_wrappers.h \
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h \
D:/zhandui/cqdm/bubing_9/modules/referee/crc_ref.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/task.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/list.h \
D:/zhandui/cqdm/bubing_9/modules/daemon/daemon.h \
D:/zhandui/cqdm/bubing_9/bsp/log/bsp_log.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/RTT/SEGGER_RTT.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/Config/SEGGER_RTT_Conf.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/SEGGER/Config/SEGGER_RTT_Conf.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS/cmsis_os.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/task.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/queue.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/semphr.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/queue.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/event_groups.h \
D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/include/timers.h
CMakeFiles/basic_framework.elf.dir/modules/remote/remote_control.c.obj: D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.c \
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.h \
D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/lib/gcc/arm-none-eabi/10.3.1/include/stdint.h \
@ -9032,6 +9159,8 @@ D:/zhandui/cqdm/bubing_9/modules/imu/ins_task.c:
D:/zhandui/cqdm/bubing_9/modules/auto_aim/auto_aim.h:
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h:
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.c:
D:/zhandui/cqdm/bubing_9/application/gimbal/gimbal.h:
@ -9152,6 +9281,8 @@ D:/zhandui/cqdm/bubing_9/modules/super_cap/super_cap.c:
D:/zhandui/cqdm/bubing_9/modules/referee/rm_referee.c:
D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c:
D:/zhandui/cqdm/bubing_9/modules/remote/remote_control.c:
D:/zhandui/cqdm/bubing_9/modules/unicomm/unicomm.c:

File diff suppressed because one or more lines are too long

View File

@ -19,8 +19,8 @@ CMAKE_PROGRESS_18 =
CMAKE_PROGRESS_19 = 14
CMAKE_PROGRESS_20 = 15
CMAKE_PROGRESS_21 = 16
CMAKE_PROGRESS_22 = 17
CMAKE_PROGRESS_23 =
CMAKE_PROGRESS_22 =
CMAKE_PROGRESS_23 = 17
CMAKE_PROGRESS_24 = 18
CMAKE_PROGRESS_25 = 19
CMAKE_PROGRESS_26 = 20
@ -28,103 +28,104 @@ CMAKE_PROGRESS_27 =
CMAKE_PROGRESS_28 = 21
CMAKE_PROGRESS_29 = 22
CMAKE_PROGRESS_30 = 23
CMAKE_PROGRESS_31 = 24
CMAKE_PROGRESS_32 =
CMAKE_PROGRESS_31 =
CMAKE_PROGRESS_32 = 24
CMAKE_PROGRESS_33 = 25
CMAKE_PROGRESS_34 = 26
CMAKE_PROGRESS_35 = 27
CMAKE_PROGRESS_36 =
CMAKE_PROGRESS_35 =
CMAKE_PROGRESS_36 = 27
CMAKE_PROGRESS_37 = 28
CMAKE_PROGRESS_38 = 29
CMAKE_PROGRESS_39 = 30
CMAKE_PROGRESS_40 = 31
CMAKE_PROGRESS_41 =
CMAKE_PROGRESS_40 =
CMAKE_PROGRESS_41 = 31
CMAKE_PROGRESS_42 = 32
CMAKE_PROGRESS_43 = 33
CMAKE_PROGRESS_44 = 34
CMAKE_PROGRESS_45 =
CMAKE_PROGRESS_44 =
CMAKE_PROGRESS_45 = 34
CMAKE_PROGRESS_46 = 35
CMAKE_PROGRESS_47 = 36
CMAKE_PROGRESS_48 = 37
CMAKE_PROGRESS_49 =
CMAKE_PROGRESS_48 =
CMAKE_PROGRESS_49 = 37
CMAKE_PROGRESS_50 = 38
CMAKE_PROGRESS_51 = 39
CMAKE_PROGRESS_52 = 40
CMAKE_PROGRESS_53 = 41
CMAKE_PROGRESS_54 =
CMAKE_PROGRESS_53 =
CMAKE_PROGRESS_54 = 41
CMAKE_PROGRESS_55 = 42
CMAKE_PROGRESS_56 = 43
CMAKE_PROGRESS_57 = 44
CMAKE_PROGRESS_58 =
CMAKE_PROGRESS_57 =
CMAKE_PROGRESS_58 = 44
CMAKE_PROGRESS_59 = 45
CMAKE_PROGRESS_60 = 46
CMAKE_PROGRESS_61 = 47
CMAKE_PROGRESS_62 = 48
CMAKE_PROGRESS_63 =
CMAKE_PROGRESS_61 =
CMAKE_PROGRESS_62 = 47
CMAKE_PROGRESS_63 = 48
CMAKE_PROGRESS_64 = 49
CMAKE_PROGRESS_65 = 50
CMAKE_PROGRESS_66 = 51
CMAKE_PROGRESS_67 =
CMAKE_PROGRESS_66 =
CMAKE_PROGRESS_67 = 51
CMAKE_PROGRESS_68 = 52
CMAKE_PROGRESS_69 = 53
CMAKE_PROGRESS_70 = 54
CMAKE_PROGRESS_71 = 55
CMAKE_PROGRESS_72 =
CMAKE_PROGRESS_70 =
CMAKE_PROGRESS_71 = 54
CMAKE_PROGRESS_72 = 55
CMAKE_PROGRESS_73 = 56
CMAKE_PROGRESS_74 = 57
CMAKE_PROGRESS_75 = 58
CMAKE_PROGRESS_76 =
CMAKE_PROGRESS_74 =
CMAKE_PROGRESS_75 = 57
CMAKE_PROGRESS_76 = 58
CMAKE_PROGRESS_77 = 59
CMAKE_PROGRESS_78 = 60
CMAKE_PROGRESS_79 = 61
CMAKE_PROGRESS_80 = 62
CMAKE_PROGRESS_81 =
CMAKE_PROGRESS_79 =
CMAKE_PROGRESS_80 = 61
CMAKE_PROGRESS_81 = 62
CMAKE_PROGRESS_82 = 63
CMAKE_PROGRESS_83 = 64
CMAKE_PROGRESS_84 = 65
CMAKE_PROGRESS_85 =
CMAKE_PROGRESS_83 =
CMAKE_PROGRESS_84 = 64
CMAKE_PROGRESS_85 = 65
CMAKE_PROGRESS_86 = 66
CMAKE_PROGRESS_87 = 67
CMAKE_PROGRESS_88 = 68
CMAKE_PROGRESS_89 =
CMAKE_PROGRESS_87 =
CMAKE_PROGRESS_88 = 67
CMAKE_PROGRESS_89 = 68
CMAKE_PROGRESS_90 = 69
CMAKE_PROGRESS_91 = 70
CMAKE_PROGRESS_92 = 71
CMAKE_PROGRESS_93 = 72
CMAKE_PROGRESS_94 =
CMAKE_PROGRESS_92 =
CMAKE_PROGRESS_93 = 71
CMAKE_PROGRESS_94 = 72
CMAKE_PROGRESS_95 = 73
CMAKE_PROGRESS_96 = 74
CMAKE_PROGRESS_97 = 75
CMAKE_PROGRESS_98 =
CMAKE_PROGRESS_96 =
CMAKE_PROGRESS_97 = 74
CMAKE_PROGRESS_98 = 75
CMAKE_PROGRESS_99 = 76
CMAKE_PROGRESS_100 = 77
CMAKE_PROGRESS_101 = 78
CMAKE_PROGRESS_102 = 79
CMAKE_PROGRESS_103 =
CMAKE_PROGRESS_100 =
CMAKE_PROGRESS_101 = 77
CMAKE_PROGRESS_102 = 78
CMAKE_PROGRESS_103 = 79
CMAKE_PROGRESS_104 = 80
CMAKE_PROGRESS_105 = 81
CMAKE_PROGRESS_106 = 82
CMAKE_PROGRESS_107 =
CMAKE_PROGRESS_105 =
CMAKE_PROGRESS_106 = 81
CMAKE_PROGRESS_107 = 82
CMAKE_PROGRESS_108 = 83
CMAKE_PROGRESS_109 = 84
CMAKE_PROGRESS_110 = 85
CMAKE_PROGRESS_111 = 86
CMAKE_PROGRESS_112 =
CMAKE_PROGRESS_113 = 87
CMAKE_PROGRESS_114 = 88
CMAKE_PROGRESS_115 = 89
CMAKE_PROGRESS_116 =
CMAKE_PROGRESS_109 =
CMAKE_PROGRESS_110 = 84
CMAKE_PROGRESS_111 = 85
CMAKE_PROGRESS_112 = 86
CMAKE_PROGRESS_113 =
CMAKE_PROGRESS_114 = 87
CMAKE_PROGRESS_115 = 88
CMAKE_PROGRESS_116 = 89
CMAKE_PROGRESS_117 = 90
CMAKE_PROGRESS_118 = 91
CMAKE_PROGRESS_119 = 92
CMAKE_PROGRESS_120 = 93
CMAKE_PROGRESS_121 =
CMAKE_PROGRESS_122 = 94
CMAKE_PROGRESS_123 = 95
CMAKE_PROGRESS_124 = 96
CMAKE_PROGRESS_125 =
CMAKE_PROGRESS_126 = 97
CMAKE_PROGRESS_127 = 98
CMAKE_PROGRESS_128 = 99
CMAKE_PROGRESS_129 = 100
CMAKE_PROGRESS_118 =
CMAKE_PROGRESS_119 = 91
CMAKE_PROGRESS_120 = 92
CMAKE_PROGRESS_121 = 93
CMAKE_PROGRESS_122 =
CMAKE_PROGRESS_123 = 94
CMAKE_PROGRESS_124 = 95
CMAKE_PROGRESS_125 = 96
CMAKE_PROGRESS_126 =
CMAKE_PROGRESS_127 = 97
CMAKE_PROGRESS_128 = 98
CMAKE_PROGRESS_129 = 99
CMAKE_PROGRESS_130 = 100

View File

@ -1,19 +1,5 @@
"D:\clion\CLion 2023.2.2\bin\cmake\win\x64\bin\cmake.exe" -DCMAKE_BUILD_TYPE=Debug -DCMAKE_MAKE_PROGRAM=D:/MinGW/mingw64/bin/mingw32-make.exe -DCMAKE_C_COMPILER=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe -DCMAKE_CXX_COMPILER=D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-g++.exe -G "CodeBlocks - MinGW Makefiles" -S D:\zhandui\cqdm\bubing_9 -B D:\zhandui\cqdm\bubing_9\cmake-build-debug
-- The C compiler identification is GNU 10.3.1
-- The CXX compiler identification is GNU 10.3.1
-- The ASM compiler identification is GNU
-- Found assembler: D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working C compiler: D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe - skipped
-- Detecting C compile features
-- Detecting C compile features - done
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Check for working CXX compiler: D:/gcc-arm-none-eabi-10.3-2021.10-win32/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-g++.exe - skipped
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Minimal optimization, debug info included
-- Configuring done (1.7s)
-- Configuring done (0.2s)
-- Generating done (0.1s)
-- Build files have been written to: D:/zhandui/cqdm/bubing_9/cmake-build-debug

View File

@ -3048,6 +3048,30 @@ modules/referee/rm_referee.c.s:
$(MAKE) $(MAKESILENT) -f CMakeFiles\basic_framework.elf.dir\build.make CMakeFiles/basic_framework.elf.dir/modules/referee/rm_referee.c.s
.PHONY : modules/referee/rm_referee.c.s
modules/referee/vision_transfer.obj: modules/referee/vision_transfer.c.obj
.PHONY : modules/referee/vision_transfer.obj
# target to build an object file
modules/referee/vision_transfer.c.obj:
$(MAKE) $(MAKESILENT) -f CMakeFiles\basic_framework.elf.dir\build.make CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.obj
.PHONY : modules/referee/vision_transfer.c.obj
modules/referee/vision_transfer.i: modules/referee/vision_transfer.c.i
.PHONY : modules/referee/vision_transfer.i
# target to preprocess a source file
modules/referee/vision_transfer.c.i:
$(MAKE) $(MAKESILENT) -f CMakeFiles\basic_framework.elf.dir\build.make CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.i
.PHONY : modules/referee/vision_transfer.c.i
modules/referee/vision_transfer.s: modules/referee/vision_transfer.c.s
.PHONY : modules/referee/vision_transfer.s
# target to generate assembly for a file
modules/referee/vision_transfer.c.s:
$(MAKE) $(MAKESILENT) -f CMakeFiles\basic_framework.elf.dir\build.make CMakeFiles/basic_framework.elf.dir/modules/referee/vision_transfer.c.s
.PHONY : modules/referee/vision_transfer.c.s
modules/remote/remote_control.obj: modules/remote/remote_control.c.obj
.PHONY : modules/remote/remote_control.obj
@ -3542,6 +3566,9 @@ help:
@echo ... modules/referee/rm_referee.obj
@echo ... modules/referee/rm_referee.i
@echo ... modules/referee/rm_referee.s
@echo ... modules/referee/vision_transfer.obj
@echo ... modules/referee/vision_transfer.i
@echo ... modules/referee/vision_transfer.s
@echo ... modules/remote/remote_control.obj
@echo ... modules/remote/remote_control.i
@echo ... modules/remote/remote_control.s

View File

@ -1210,6 +1210,12 @@
<Unit filename="D:/zhandui/cqdm/bubing_9/modules/referee/rm_referee.h">
<Option target="basic_framework.elf"/>
</Unit>
<Unit filename="D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.c">
<Option target="basic_framework.elf"/>
</Unit>
<Unit filename="D:/zhandui/cqdm/bubing_9/modules/referee/vision_transfer.h">
<Option target="basic_framework.elf"/>
</Unit>
<Unit filename="D:/zhandui/cqdm/bubing_9/modules/remote/remote.md">
<Option target="basic_framework.elf"/>
</Unit>

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -147,9 +147,9 @@ static void DecodeVision(uint16_t recv_len)
}
/* 视觉通信初始化 */
RecievePacket_t *VisionInit(UART_HandleTypeDef *_handle)
RecievePacket_t *VisionInit(void)
{
UNUSED(_handle); // 仅为了消除警告
// UNUSED(_handle); // 仅为了消除警告
USB_Init_Config_s conf = {.rx_cbk = DecodeVision};
vis_recv_buff = USBInit(conf);

View File

@ -113,7 +113,7 @@ typedef __packed struct {
* @param handle handle(C板上一般为USART1,USART2,4pin)
*/
//Vision_Recv_s *VisionInit(UART_HandleTypeDef *_handle);
RecievePacket_t *VisionInit(UART_HandleTypeDef *_handle);
RecievePacket_t *VisionInit(void);
/**
* @brief

View File

@ -286,7 +286,13 @@ void DJIMotorControl() {
if (motor_setting->angle_feedback_source == OTHER_FEED)
pid_measure = *motor_controller->other_angle_feedback_ptr;
else
pid_measure = measure->total_angle; // MOTOR_FEED,对total angle闭环,防止在边界处出现突跃
{
if(motor_setting->feedback_reverse_flag == FEEDBACK_DIRECTION_REVERSE)
pid_measure = -measure->total_angle;
else
pid_measure = measure->total_angle; // MOTOR_FEED,对total angle闭环,防止在边界处出现突跃
}
// 更新pid_ref进入下一个环
pid_ref = PIDCalculate(&motor_controller->angle_PID, pid_measure, pid_ref);
}
@ -300,7 +306,13 @@ void DJIMotorControl() {
if (motor_setting->speed_feedback_source == OTHER_FEED)
pid_measure = *motor_controller->other_speed_feedback_ptr;
else // MOTOR_FEED
pid_measure = measure->speed_aps;
{
if(motor_setting->feedback_reverse_flag == FEEDBACK_DIRECTION_REVERSE)
pid_measure = -measure->speed_aps;
else
pid_measure = measure->speed_aps;
}
// 更新pid_ref进入下一个环
pid_ref = PIDCalculate(&motor_controller->speed_PID, pid_measure, pid_ref);
}

View File

@ -65,7 +65,7 @@ typedef struct
/****************************cmd_id命令码说明****************************/
/****************************cmd_id命令码说明****************************/
// V1.6.1 裁判系统串口协议
/* 命令码ID,用来判断接收的是什么数据 */
typedef enum
{
@ -83,24 +83,28 @@ typedef enum
ID_robot_hurt = 0x0206, // 伤害状态数据
ID_shoot_data = 0x0207, // 实时射击数据
ID_student_interactive = 0x0301, // 机器人间交互数据
ID_custom_robot = 0x302, // 自定义控制器数据(图传链路)
ID_remote_control = 0x304, // 键鼠遥控数据(图传链路)
} CmdID_e;
/* 命令码数据段长,根据官方协议来定义长度,还有自定义数据长度 */
typedef enum
{
LEN_game_state = 3, // 0x0001
LEN_game_state = 11, // 0x0001
LEN_game_result = 1, // 0x0002
LEN_game_robot_HP = 2, // 0x0003
LEN_game_robot_HP = 32, // 0x0003
LEN_event_data = 4, // 0x0101
LEN_supply_projectile_action = 4, // 0x0102
LEN_game_robot_state = 27, // 0x0201
LEN_power_heat_data = 14, // 0x0202
LEN_game_robot_state = 13, // 0x0201
LEN_power_heat_data = 16, // 0x0202
LEN_game_robot_pos = 16, // 0x0203
LEN_buff_musk = 1, // 0x0204
LEN_aerial_robot_energy = 1, // 0x0205
LEN_buff_musk = 6, // 0x0204
LEN_aerial_robot_energy = 2, // 0x0205
LEN_robot_hurt = 1, // 0x0206
LEN_shoot_data = 7, // 0x0207
LEN_receive_data = 6 + Communicate_Data_LEN, // 0x0301
LEN__custom_robot = 30, // 0x0302
LEN_remote_control = 12, // 0x0304
} JudgeDataLength_e;
@ -124,23 +128,23 @@ typedef struct
/* ID: 0x0003 Byte: 32 比赛机器人血量数据 */
typedef struct
{
uint16_t red_1_robot_HP;
uint16_t red_2_robot_HP;
uint16_t red_3_robot_HP;
uint16_t red_4_robot_HP;
uint16_t red_5_robot_HP;
uint16_t red_7_robot_HP;
uint16_t red_outpost_HP;
uint16_t red_base_HP;
uint16_t blue_1_robot_HP;
uint16_t blue_2_robot_HP;
uint16_t blue_3_robot_HP;
uint16_t blue_4_robot_HP;
uint16_t blue_5_robot_HP;
uint16_t blue_7_robot_HP;
uint16_t blue_outpost_HP;
uint16_t blue_base_HP;
} ext_game_robot_HP_t;
uint16_t red_1_robot_HP;
uint16_t red_2_robot_HP;
uint16_t red_3_robot_HP;
uint16_t red_4_robot_HP;
uint16_t red_5_robot_HP;
uint16_t red_7_robot_HP;
uint16_t red_outpost_HP;
uint16_t red_base_HP;
uint16_t blue_1_robot_HP;
uint16_t blue_2_robot_HP;
uint16_t blue_3_robot_HP;
uint16_t blue_4_robot_HP;
uint16_t blue_5_robot_HP;
uint16_t blue_7_robot_HP;
uint16_t blue_outpost_HP;
uint16_t blue_base_HP;
}ext_game_robot_HP_t;
/* ID: 0x0101 Byte: 4 场地事件数据 */
typedef struct
@ -148,7 +152,7 @@ typedef struct
uint32_t event_type;
} ext_event_data_t;
/* ID: 0x0102 Byte: 3 场地补给站动作标识数据 */
/* ID: 0x0102 Byte: 4 场地补给站动作标识数据 */
typedef struct
{
uint8_t supply_projectile_id;
@ -157,7 +161,7 @@ typedef struct
uint8_t supply_projectile_num;
} ext_supply_projectile_action_t;
/* ID: 0X0201 Byte: 13 V1.6.1 机器人性能体系数据 */
/* ID: 0X0201 Byte: 13 机器人性能体系数据 */
typedef struct
{
uint8_t robot_id;
@ -173,7 +177,7 @@ typedef struct
uint8_t power_management_shooter_output : 1;
} ext_game_robot_state_t;
/* ID: 0X0202 Byte: 14 v1.6.1 实时功率热量数据 */
/* ID: 0X0202 Byte: 16 实时功率热量数据 */
typedef struct
{
uint16_t chassis_voltage;
@ -194,16 +198,22 @@ typedef struct
float yaw;
} ext_game_robot_pos_t;
/* ID: 0x0204 Byte: 1 机器人增益数据 */
/* ID: 0x0204 Byte: 6 机器人增益数据 */
typedef struct
{
uint8_t power_rune_buff;
uint8_t recovery_buff;
uint8_t cooling_buff;
uint8_t defence_buff;
uint8_t vulnerability_buff;
uint16_t attack_buff;
uint8_t power_rune_buff;
} ext_buff_musk_t;
/* ID: 0x0205 Byte: 1 空中机器人能量状态数据 */
/* ID: 0x0205 Byte: 2 空中机器人能量状态数据 */
typedef struct
{
uint8_t attack_time;
uint8_t airforce_status;
uint8_t time_remain;
} aerial_robot_energy_t;
/* ID: 0x0206 Byte: 1 伤害状态数据 */
@ -222,6 +232,20 @@ typedef struct
float bullet_speed;
} ext_shoot_data_t;
/****************************图传链路数据****************************/
/* ID: 0x0304 Byte: 12 图传链路键鼠遥控数据 */
typedef struct
{
int16_t mouse_x;
int16_t mouse_y;
int16_t mouse_z;
int8_t left_button_down;
int8_t right_button_down;
uint16_t keyboard_value;
uint16_t reserved;
}vision_transfer_t;
/****************************图传链路数据****************************/
/****************************机器人交互数据****************************/
/****************************机器人交互数据****************************/
/* 发送的内容数据段最大为 113 检测是否超出大小限制?实际上图形段不会超数据段最多30个也不会超*/

View File

@ -82,7 +82,7 @@ void MyUIInit()
UICircleDraw(&UI_shoot_yuan[0],"sy0",UI_Graph_ADD,7,UI_Color_Yellow,2,960,540,10);
UIGraphRefresh(&referee_recv_info->referee_id, 5, UI_shoot_line[0], UI_shoot_line[1], UI_shoot_line[2], UI_shoot_line[3],UI_shoot_yuan[0]);
// 绘制车辆状态标志指示
// 绘制车辆状态标志指示,静态
UICharDraw(&UI_State_sta[0], "ss0", UI_Graph_ADD, 8, UI_Color_Main, 15, 2, 150, 750, "chassis:");
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[0]);
UICharDraw(&UI_State_sta[1], "ss1", UI_Graph_ADD, 8, UI_Color_Yellow, 15, 2, 150, 700, "gimbal:");
@ -93,6 +93,11 @@ void MyUIInit()
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[3]);
UICharDraw(&UI_State_sta[4], "ss4", UI_Graph_ADD, 8, UI_Color_Pink, 15, 2, 150, 550, "Q.lid:");
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[4]);
UICharDraw(&UI_State_sta[5], "ss5", UI_Graph_ADD, 8, UI_Color_Pink, 15, 2, 150, 800, "load:");
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[5]);
// 底盘功率显示,静态
UICharDraw(&UI_State_sta[6], "ss6", UI_Graph_ADD, 8, UI_Color_Green, 18, 2, 620, 230, "Power_MAX:");
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[6]);
// 绘制车辆状态标志,动态
// 由于初始化时xxx_last_mode默认为0所以此处对应UI也应该设为0时对应的UI防止模式不变的情况下无法置位flag导致UI无法刷新
@ -106,84 +111,25 @@ void MyUIInit()
UICharRefresh(&referee_recv_info->referee_id, UI_State_dyn[3]);
UICharDraw(&UI_State_dyn[4], "sd4", UI_Graph_ADD, 8, UI_Color_Pink, 15, 2, 270, 550, "open ");
UICharRefresh(&referee_recv_info->referee_id, UI_State_dyn[4]);
// 底盘功率显示,静态
UICharDraw(&UI_State_sta[5], "ss5", UI_Graph_ADD, 8, UI_Color_Green, 18, 2, 620, 230, "Power_MAX:");
UICharRefresh(&referee_recv_info->referee_id, UI_State_sta[5]);
UICharDraw(&UI_State_dyn[5], "sd5", UI_Graph_ADD, 8, UI_Color_Pink, 15, 2, 270, 800, "999");
UICharRefresh(&referee_recv_info->referee_id, UI_State_dyn[5]);
// 能量条框
UIRectangleDraw(&UI_Energy[0], "ss6", UI_Graph_ADD, 7, UI_Color_Green, 2, 720, 140, 1220, 180);
UIGraphRefresh(&referee_recv_info->referee_id, 1, UI_Energy[0]);
// 底盘功率显示,动态
UIFloatDraw(&UI_Energy[1], "sd5", UI_Graph_ADD, 8, UI_Color_Green, 18, 2, 2, 850, 230, referee_recv_info->GameRobotState.chassis_power_limit*1000);
UIFloatDraw(&UI_Energy[1], "sd6", UI_Graph_ADD, 8, UI_Color_Green, 18, 2, 2, 850, 230, referee_recv_info->GameRobotState.chassis_power_limit*1000);
UIGraphRefresh(&referee_recv_info->referee_id, 1, UI_Energy[1]);
// 能量条初始状态
UILineDraw(&UI_Energy[2], "sd6", UI_Graph_ADD, 8, UI_Color_Pink, 30, 720, 160, 1020, 160);
//UILineDraw(&UI_Energy[2], "sd6", UI_Graph_ADD, 8, UI_Color_Pink, 30, 720, 160, 1020, 160);
//超级电容电压
UIIntDraw(&UI_Energy[3],"sd7",UI_Graph_ADD,8,UI_Color_Pink,18,2,1000,300,cap->cap_msg.cap_vol);
UILineDraw(&UI_Energy[3],"sd7",UI_Graph_ADD,8,UI_Color_Pink,30,720,160,(uint32_t)(720 + (cap->cap_msg.cap_vol-1200) * 0.416),160);
UIGraphRefresh(&referee_recv_info->referee_id, 1, UI_Energy[3]);
}
// 测试用函数,实现模式自动变化,用于检查该任务和裁判系统是否连接正常
static uint8_t count = 0;
static uint16_t count1 = 0;
static void RobotModeTest(Referee_Interactive_info_t *_Interactive_data) // 测试用函数,实现模式自动变化
{
count++;
if (count >= 50)
{
count = 0;
count1++;
}
switch (count1 % 4)
{
case 0:
{
_Interactive_data->chassis_mode = CHASSIS_ZERO_FORCE;
_Interactive_data->gimbal_mode = GIMBAL_ZERO_FORCE;
_Interactive_data->shoot_mode = SHOOT_ON;
_Interactive_data->friction_mode = FRICTION_ON;
_Interactive_data->lid_mode = LID_OPEN;
_Interactive_data->Chassis_Power_Data.chassis_power_mx += 3.5;
if (_Interactive_data->Chassis_Power_Data.chassis_power_mx >= 18)
_Interactive_data->Chassis_Power_Data.chassis_power_mx = 0;
break;
}
case 1:
{
_Interactive_data->chassis_mode = CHASSIS_ROTATE;
_Interactive_data->gimbal_mode = GIMBAL_FREE_MODE;
_Interactive_data->shoot_mode = SHOOT_OFF;
_Interactive_data->friction_mode = FRICTION_OFF;
_Interactive_data->lid_mode = LID_CLOSE;
break;
}
case 2:
{
_Interactive_data->chassis_mode = CHASSIS_NO_FOLLOW;
_Interactive_data->gimbal_mode = GIMBAL_GYRO_MODE;
_Interactive_data->shoot_mode = SHOOT_ON;
_Interactive_data->friction_mode = FRICTION_ON;
_Interactive_data->lid_mode = LID_OPEN;
break;
}
case 3:
{
_Interactive_data->chassis_mode = CHASSIS_FOLLOW_GIMBAL_YAW;
_Interactive_data->gimbal_mode = GIMBAL_ZERO_FORCE;
_Interactive_data->shoot_mode = SHOOT_OFF;
_Interactive_data->friction_mode = FRICTION_OFF;
_Interactive_data->lid_mode = LID_CLOSE;
break;
}
default:
break;
}
}
static void MyUIRefresh(referee_info_t *referee_recv_info, Referee_Interactive_info_t *_Interactive_data)
{
UIChangeCheck(_Interactive_data);
@ -254,13 +200,43 @@ static void MyUIRefresh(referee_info_t *referee_recv_info, Referee_Interactive_i
UICharRefresh(&referee_recv_info->referee_id, UI_State_dyn[4]);
_Interactive_data->Referee_Interactive_Flag.lid_flag = 0;
}
// load_mode
if (_Interactive_data->Referee_Interactive_Flag.load_flag == 1)
{
switch (_Interactive_data->loader_mode)
{
case LOAD_1_BULLET:
{
UICharDraw(&UI_State_dyn[5], "sd5", UI_Graph_Change, 8, UI_Color_Pink, 15, 2, 270, 800, " 1 ");
break;
}
case LOAD_3_BULLET:
{
UICharDraw(&UI_State_dyn[5], "sd5", UI_Graph_Change, 8, UI_Color_Pink, 15, 2, 270, 800, " 3 ");
break;
}
case LOAD_BURSTFIRE:
{
UICharDraw(&UI_State_dyn[5], "sd5", UI_Graph_Change, 8, UI_Color_Pink, 15, 2, 270, 800, "999");
break;
}
}
UICharRefresh(&referee_recv_info->referee_id, UI_State_dyn[5]);
_Interactive_data->Referee_Interactive_Flag.load_flag = 0;
}
// power
if (_Interactive_data->Referee_Interactive_Flag.Power_flag == 1)
{
UIFloatDraw(&UI_Energy[1], "sd5", UI_Graph_Change, 8, UI_Color_Green, 18, 2, 2, 850, 230, _Interactive_data->Chassis_Power_Data.chassis_power_mx * 1000);
UILineDraw(&UI_Energy[2], "sd6", UI_Graph_Change, 8, UI_Color_Pink, 30, 720, 160, (uint32_t)750 + cap->cap_msg.cap_vol * 30, 160);
UIGraphRefresh(&referee_recv_info->referee_id, 2, UI_Energy[1], UI_Energy[2]);
_Interactive_data->Referee_Interactive_Flag.Power_flag = 0;
UIFloatDraw(&UI_Energy[1], "sd6", UI_Graph_Change, 8, UI_Color_Green, 18, 2, 2, 850, 230, _Interactive_data->Chassis_Power_Data.chassis_power_mx * 1000);
UIGraphRefresh(&referee_recv_info->referee_id, 2, UI_Energy[1]);
_Interactive_data->Referee_Interactive_Flag.cap_flag = 0;
}
// cap
if (_Interactive_data->Referee_Interactive_Flag.cap_flag == 1)
{
UILineDraw(&UI_Energy[3], "sd7", UI_Graph_Change, 8, UI_Color_Pink, 30, 720, 160, (uint32_t)(720 + (cap->cap_msg.cap_vol-1200) * 0.416), 160);
UIGraphRefresh(&referee_recv_info->referee_id, 2, UI_Energy[3]);
_Interactive_data->Referee_Interactive_Flag.cap_flag = 0;
}
//绘制开火建议
if (_Interactive_data->Referee_Interactive_Flag.aim_flag == 1) {
@ -325,4 +301,10 @@ static void UIChangeCheck(Referee_Interactive_info_t *_Interactive_data)
_Interactive_data->Referee_Interactive_Flag.aim_flag = 1;
_Interactive_data->aim_last_fire = _Interactive_data->aim_fire;
}
if (_Interactive_data->loader_mode != _Interactive_data->loader_last_mode)
{
_Interactive_data->Referee_Interactive_Flag.load_flag = 1;
_Interactive_data->loader_last_mode = _Interactive_data->loader_mode;
}
}

View File

@ -58,6 +58,7 @@ typedef struct
uint32_t Power_flag : 1;
uint32_t aim_flag : 1;
uint32_t cap_flag : 1;
uint32_t load_flag : 1;
} Referee_Interactive_Flag_t;
// 此结构体包含UI绘制与机器人车间通信的需要的其他非裁判系统数据
@ -67,11 +68,12 @@ typedef struct
// 为UI绘制以及交互数据所用
chassis_mode_e chassis_mode; // 底盘模式
gimbal_mode_e gimbal_mode; // 云台模式
shoot_mode_e shoot_mode; // 发射模式设置
shoot_mode_e shoot_mode; // 发射开关设置
friction_mode_e friction_mode; // 摩擦轮关闭
lid_mode_e lid_mode; // 弹舱盖打开
Chassis_Power_Data_s Chassis_Power_Data; // 功率控制
uint8_t aim_fire; // 开火建议
loader_mode_e loader_mode; // 发射模式
// 上一次的模式用于flag判断
@ -82,6 +84,7 @@ typedef struct
lid_mode_e lid_last_mode;
Chassis_Power_Data_s Chassis_last_Power_Data;
uint8_t aim_last_fire;
loader_mode_e loader_last_mode;
} Referee_Interactive_info_t;

View File

@ -0,0 +1,162 @@
/**
* @file rm_referee.C
* @author kidneygood (you@domain.com)
* @brief
* @version 0.1
* @date 2022-11-18
*
* @copyright Copyright (c) 2022
*
*/
#include "vision_transfer.h"
#include "string.h"
#include "crc_ref.h"
#include "bsp_usart.h"
#include "task.h"
#include "daemon.h"
#include "bsp_log.h"
#include "cmsis_os.h"
#include "remote_control.h"
#define RE_RX_BUFFER_SIZE 128u // 裁判系统接收缓冲区大小
static USARTInstance *vt_usart_instance; // 裁判系统串口实例
static DaemonInstance *vision_transfer_daemon; // 裁判系统守护进程
static referee_info_vt_t referee_info_vt; // 裁判系统数据
static VT_ctrl_t vt_ctrl[2]; //[0]:当前数据TEMP,[1]:上一次的数据LAST.用于按键持续按下和切换的判断
/**
* @brief ,
* @param buff:
* @retval
* @attention CRC校验,
*/
static void JudgeReadVTData(uint8_t *buff)
{
uint16_t judge_length; // 统计一帧数据长度
if (buff == NULL) // 空数据包,则不作任何处理
return;
// 写入帧头数据(5-byte),用于判断是否开始存储裁判数据
memcpy(&referee_info_vt.FrameHeader, buff, LEN_HEADER);
// 判断帧头数据(0)是否为0xA5
if (buff[SOF] == REFEREE_SOF)
{
// 帧头CRC8校验
if (Verify_CRC8_Check_Sum(buff, LEN_HEADER) == TRUE)
{
// 统计一帧数据长度(byte),用于CR16校验
judge_length = buff[DATA_LENGTH] + LEN_HEADER + LEN_CMDID + LEN_TAIL;
// 帧尾CRC16校验
if (Verify_CRC16_Check_Sum(buff, judge_length) == TRUE)
{
// 2个8位拼成16位int
referee_info_vt.CmdID = (buff[6] << 8 | buff[5]);
// 解析数据命令码,将数据拷贝到相应结构体中(注意拷贝数据的长度)
// 第8个字节开始才是数据 data=7
switch (referee_info_vt.CmdID)
{
case ID_custom_robot: //0x0302
memcpy(&referee_info_vt.ReceiveData, (buff + DATA_Offset), LEN__custom_robot);
break;
case ID_remote_control: //0x0304
memcpy(&referee_info_vt.VisionTransfer, (buff + DATA_Offset), LEN_remote_control);
break;
}
}
}
// 首地址加帧长度,指向CRC16下一字节,用来判断是否为0xA5,从而判断一个数据包是否有多帧数据
if (*(buff + sizeof(xFrameHeader) + LEN_CMDID + referee_info_vt.FrameHeader.DataLength + LEN_TAIL) == 0xA5)
{ // 如果一个数据包出现了多帧数据,则再次调用解析函数,直到所有数据包解析完毕
JudgeReadVTData(buff + sizeof(xFrameHeader) + LEN_CMDID + referee_info_vt.FrameHeader.DataLength + LEN_TAIL);
}
}
}
static void vt_to_rc(void)
{
// 鼠标解析
vt_ctrl[TEMP].mouse.x = referee_info_vt.VisionTransfer.mouse_x; //!< Mouse X axis
vt_ctrl[TEMP].mouse.y = referee_info_vt.VisionTransfer.mouse_y; //!< Mouse Y axis
vt_ctrl[TEMP].mouse.press_l = referee_info_vt.VisionTransfer.left_button_down; //!< Mouse Left Is Press ?
vt_ctrl[TEMP].mouse.press_r = referee_info_vt.VisionTransfer.right_button_down; //!< Mouse Right Is Press ?
// 位域的按键值解算,直接memcpy即可,注意小端低字节在前,即lsb在第一位,msb在最后
*(uint16_t *)&vt_ctrl[TEMP].key[KEY_PRESS] = referee_info_vt.VisionTransfer.keyboard_value;
if (vt_ctrl[TEMP].key[KEY_PRESS].ctrl) // ctrl键按下
vt_ctrl[TEMP].key[KEY_PRESS_WITH_CTRL] = vt_ctrl[TEMP].key[KEY_PRESS];
else
memset(&vt_ctrl[TEMP].key[KEY_PRESS_WITH_CTRL], 0, sizeof(Key_t));
if (vt_ctrl[TEMP].key[KEY_PRESS].shift) // shift键按下
vt_ctrl[TEMP].key[KEY_PRESS_WITH_SHIFT] = vt_ctrl[TEMP].key[KEY_PRESS];
else
memset(&vt_ctrl[TEMP].key[KEY_PRESS_WITH_SHIFT], 0, sizeof(Key_t));
uint16_t key_now = vt_ctrl[TEMP].key[KEY_PRESS].keys, // 当前按键是否按下
key_last = vt_ctrl[LAST].key[KEY_PRESS].keys, // 上一次按键是否按下
key_with_ctrl = vt_ctrl[TEMP].key[KEY_PRESS_WITH_CTRL].keys, // 当前ctrl组合键是否按下
key_with_shift = vt_ctrl[TEMP].key[KEY_PRESS_WITH_SHIFT].keys, // 当前shift组合键是否按下
key_last_with_ctrl = vt_ctrl[LAST].key[KEY_PRESS_WITH_CTRL].keys, // 上一次ctrl组合键是否按下
key_last_with_shift = vt_ctrl[LAST].key[KEY_PRESS_WITH_SHIFT].keys; // 上一次shift组合键是否按下
for (uint16_t i = 0, j = 0x1; i < 16; j <<= 1, i++)
{
if (i == 4 || i == 5) // 4,5位为ctrl和shift,直接跳过
continue;
// 如果当前按键按下,上一次按键没有按下,且ctrl和shift组合键没有按下,则按键按下计数加1(检测到上升沿)
if ((key_now & j) && !(key_last & j) && !(key_with_ctrl & j) && !(key_with_shift & j))
vt_ctrl[TEMP].key_count[KEY_PRESS][i]++;
// 当前ctrl组合键按下,上一次ctrl组合键没有按下,则ctrl组合键按下计数加1(检测到上升沿)
if ((key_with_ctrl & j) && !(key_last_with_ctrl & j))
vt_ctrl[TEMP].key_count[KEY_PRESS_WITH_CTRL][i]++;
// 当前shift组合键按下,上一次shift组合键没有按下,则shift组合键按下计数加1(检测到上升沿)
if ((key_with_shift & j) && !(key_last_with_shift & j))
vt_ctrl[TEMP].key_count[KEY_PRESS_WITH_SHIFT][i]++;
}
memcpy(&vt_ctrl[LAST], &vt_ctrl[TEMP], sizeof(VT_ctrl_t)); // 保存上一次的数据,用于按键持续按下和切换的判断
}
/*裁判系统串口接收回调函数,解析数据 */
static void VTRefereeRxCallback()
{
DaemonReload(vision_transfer_daemon);
JudgeReadVTData(vt_usart_instance->recv_buff);
vt_to_rc();
}
// 裁判系统丢失回调函数,重新初始化裁判系统串口
static void VTRefereeLostCallback(void *arg)
{
USARTServiceInit(vt_usart_instance);
LOGWARNING("[rm_ref] lost referee vision data ");
}
/* 裁判系统通信初始化 */
VT_ctrl_t *VTRefereeInit(UART_HandleTypeDef *vt_usart_handle)
{
USART_Init_Config_s conf;
conf.module_callback = VTRefereeRxCallback;
conf.usart_handle = vt_usart_handle;
conf.recv_buff_size = RE_RX_BUFFER_SIZE; // mx 255(u8)
vt_usart_instance = USARTRegister(&conf);
Daemon_Init_Config_s daemon_conf = {
.callback = VTRefereeLostCallback,
.owner_id = vt_usart_instance,
.reload_count = 30, // 0.3s没有收到数据,则认为丢失,重启串口接收
};
vision_transfer_daemon = DaemonRegister(&daemon_conf);
return &vt_ctrl;
}
/**
* @brief
* @param
*/
void VTRefereeSend(uint8_t *send, uint16_t tx_len)
{
USARTSend(vt_usart_instance, send, tx_len, USART_TRANSFER_DMA);
osDelay(115);
}

View File

@ -0,0 +1,46 @@
#ifndef VISION_TRANSFER_H
#define VISION_TRANSFER_H
#include "usart.h"
#include "referee_protocol.h"
#include "robot_def.h"
#include "bsp_usart.h"
#include "FreeRTOS.h"
#include "remote_control.h"
#pragma pack(1)
// 此结构体包含裁判系统接收数据以及UI绘制与机器人车间通信的相关信息
typedef struct
{
xFrameHeader FrameHeader; // 接收到的帧头信息
uint16_t CmdID;
vision_transfer_t VisionTransfer;
Communicate_ReceiveData_t ReceiveData;
uint8_t init_flag;
} referee_info_vt_t;
#pragma pack()
/**
* @brief ,,
*
* @param vt_usart_handle handle,C板一般用串口6
* @return referee_info_t* ,//
*/
VT_ctrl_t *VTRefereeInit(UART_HandleTypeDef *referee_usart_handle);
/**
* @brief UI绘制和交互数的发送接口,UI绘制任务和多机通信函数调用
* @note ,CMD数据至高位10Hz
*
* @param send
* @param tx_len
*/
void VTRefereeSend(uint8_t *send, uint16_t tx_len);
#endif // !REFEREE_H

View File

@ -16,6 +16,10 @@ static uint8_t rc_init_flag = 0; // 遥控器初始化标志位
static USARTInstance *rc_usart_instance;
static DaemonInstance *rc_daemon_instance;
// 图传拥有的串口实例
static USARTInstance *vt_usart_instance;
static DaemonInstance *vt_daemon_instance;
/**
* @brief ,660-660,0
*
@ -97,6 +101,12 @@ static void RemoteControlRxCallback()
sbus_to_rc(rc_usart_instance->recv_buff); // 进行协议解析
}
//static void RemoteControlvtCallback()
//{
// DaemonReload(vt_daemon_instance); // 先喂狗
// sbus_to_rc(vt_usart_instance->recv_buff); // 进行协议解析
//}
/**
* @brief 线,,线
*

View File

@ -113,6 +113,20 @@ typedef struct
uint8_t key_count[3][16];
} RC_ctrl_t;
typedef struct
{
struct
{
int16_t x;
int16_t y;
uint8_t press_l;
uint8_t press_r;
} mouse;
Key_t key[3];
uint8_t key_count[3][16];
}VT_ctrl_t; //图传链路下发的遥控数据
/* ------------------------- Internal Data ----------------------------------- */
/**
@ -123,6 +137,8 @@ typedef struct
*/
RC_ctrl_t *RemoteControlInit(UART_HandleTypeDef *rc_usart_handle);
//VT_ctrl_t *RemoteControlInit(UART_HandleTypeDef *vt_usart_handle);
/**
* @brief 线,线
*

View File

@ -1,31 +0,0 @@
GraphedExpression="(((pitch_motor)->motor_controller).speed_PID).Ref", Color=#a00909
GraphedExpression="(((pitch_motor)->motor_controller).speed_PID).Measure", Color=#09a01b
OpenDocument="main.c", FilePath="D:/zhandui/cqdm/basic_framework/Src/main.c", Line=64
OpenDocument="tasks.c", FilePath="D:/zhandui/cqdm/basic_framework/Middlewares/Third_Party/FreeRTOS/Source/tasks.c", Line=3623
OpenDocument="controller.h", FilePath="D:/zhandui/cqdm/basic_framework/modules/algorithm/controller.h", Line=48
OpenDocument="robot_def.h", FilePath="D:/zhandui/cqdm/basic_framework/application/robot_def.h", Line=9
OpenDocument="chassis.c", FilePath="D:/zhandui/cqdm/basic_framework/application/chassis/chassis.c", Line=0
OpenDocument="gimbal.c", FilePath="D:/zhandui/cqdm/basic_framework/application/gimbal/gimbal.c", Line=141
OpenDocument="startup_stm32f407ighx.s", FilePath="D:/zhandui/cqdm/basic_framework/Startup/startup_stm32f407ighx.s", Line=46
OpenToolbar="Debug", Floating=0, x=0, y=0
OpenWindow="Source Files", DockArea=LEFT, x=0, y=0, w=651, h=492, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Memory 1", DockArea=BOTTOM, x=2, y=0, w=831, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, EditorAddress=0x30A3D700
OpenWindow="Watched Data 1", DockArea=LEFT, x=0, y=1, w=651, h=600, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Data Sampling", DockArea=BOTTOM, x=1, y=0, w=615, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, VisibleTab=0, UniformSampleSpacing=0
OpenWindow="Timeline", DockArea=RIGHT, x=0, y=0, w=1153, h=1093, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=1, DataPaneShown=1, PowerPaneShown=0, CodePaneShown=0, PinCursor="Cursor Movable", TimePerDiv="2 s / Div", TimeStampFormat="Time", DataGraphDrawAsPoints=0, DataGraphLegendShown=0, DataGraphUniformSampleSpacing=0, DataGraphLegendPosition="0;833", PowerGraphDrawAsPoints=0, PowerGraphLegendShown=0, PowerGraphAvgFilterTime=Off, PowerGraphAvgFilterLen=Off, PowerGraphUniformSampleSpacing=0, PowerGraphLegendPosition="926;0", CodeGraphLegendShown=0, CodeGraphLegendPosition="942;0"
OpenWindow="Console", DockArea=BOTTOM, x=0, y=0, w=1112, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
TableHeader="Source Files", SortCol="File", SortOrder="ASCENDING", VisibleCols=["File";"Status";"Size";"#Insts";"Path"], ColWidths=[263;100;100;100;950]
TableHeader="Data Sampling Table", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time";" (((pitch_motor)->motor_controller).speed_PID).Ref";" (((pitch_motor)->motor_controller).speed_PID).Measure"], ColWidths=[100;100;100;289]
TableHeader="Data Sampling Setup", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Type";"Value";"Min";"Max";"Average";"# Changes";"Min. Change";"Max. Change"], ColWidths=[438;100;154;124;114;164;110;126;126]
TableHeader="Power Sampling", SortCol="Index", SortOrder="ASCENDING", VisibleCols=["Index";"Time";"Ch 0"], ColWidths=[100;100;100]
TableHeader="Task List", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Run Count";"Priority";"Status";"Timeout";"Stack Info (Free / Size)";"ID";"Mutex Count";"Notified Value";"Notify State"], ColWidths=[110;110;110;110;110;110;110;110;110;110]
TableHeader="Watched Data 1", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Value";"Location";"Refresh"], ColWidths=[238;100;104;183]
TableHeader="RegisterSelectionDialog", SortCol="None", SortOrder="ASCENDING", VisibleCols=[], ColWidths=[]
TableHeader="TargetExceptionDialog", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Address";"Description"], ColWidths=[26;26;26;26]
WatchedExpression="pitch_motor", RefreshRate=2, Window=Watched Data 1
WatchedExpression="yaw_motor", RefreshRate=2, Window=Watched Data 1
WatchedExpression="YAW_CHASSIS_ALIGN_ECD", RefreshRate=2, Window=Watched Data 1
WatchedExpression="gimba_IMU_data", RefreshRate=2, Window=Watched Data 1
WatchedExpression="gravity_current", Window=Watched Data 1
WatchedExpression="motor_rf", RefreshRate=5, Window=Watched Data 1

View File

@ -33,7 +33,7 @@ void OnProjectLoad (void) {
//
// User settings
//
Edit.SysVar (VAR_HSS_SPEED, FREQ_200_HZ);
Edit.SysVar (VAR_HSS_SPEED, FREQ_500_HZ);
Project.SetOSPlugin ("FreeRTOSPlugin_CM4");
File.Open ("$(ProjectDir)/cmake-build-debug/basic_framework.elf");
}

View File

@ -1,38 +1,42 @@
Breakpoint=D:/zhandui/cqdm/bubing_9/application/shoot/shoot.c:183:5, State=BP_STATE_DISABLED
GraphedExpression="(((motor_lf)->motor_controller).speed_PID).Measure", Color=#e56a6f
GraphedExpression="(((motor_lf)->motor_controller).speed_PID).Ref", Color=#35792b
OpenDocument="robot_cmd.c", FilePath="D:/zhandui/cqdm/bubing_9/application/cmd/robot_cmd.c", Line=387
OpenDocument="tasks.c", FilePath="D:/zhandui/cqdm/bubing_9/Middlewares/Third_Party/FreeRTOS/Source/tasks.c", Line=3418
OpenDocument="main.c", FilePath="D:/zhandui/cqdm/bubing_9/Src/main.c", Line=65
OpenDocument="chassis.c", FilePath="D:/zhandui/cqdm/bubing_9/application/chassis/chassis.c", Line=87
OpenDocument="shoot.c", FilePath="D:/zhandui/cqdm/bubing_9/application/shoot/shoot.c", Line=191
OpenDocument="super_cap.c", FilePath="D:/zhandui/cqdm/bubing_9/modules/super_cap/super_cap.c", Line=0
OpenDocument="chassis.c", FilePath="D:/zhandui/cqdm/bubing_9/application/chassis/chassis.c", Line=81
OpenDocument="shoot.c", FilePath="D:/zhandui/cqdm/bubing_9/application/shoot/shoot.c", Line=63
OpenDocument="main.c", FilePath="D:/zhandui/cqdm/bubing_9/Src/main.c", Line=64
OpenToolbar="Debug", Floating=0, x=0, y=0
OpenWindow="Source Files", DockArea=LEFT, x=0, y=0, w=556, h=292, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Disassembly", DockArea=RIGHT, x=0, y=0, w=935, h=205, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Memory 1", DockArea=BOTTOM, x=3, y=0, w=800, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, EditorAddress=0x30A3D70C
OpenWindow="Watched Data 1", DockArea=LEFT, x=0, y=1, w=556, h=800, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Terminal", DockArea=BOTTOM, x=0, y=0, w=650, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Data Sampling", DockArea=BOTTOM, x=2, y=0, w=979, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, VisibleTab=0, UniformSampleSpacing=0
OpenWindow="Timeline", DockArea=RIGHT, x=0, y=1, w=935, h=887, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=1, DataPaneShown=1, PowerPaneShown=0, CodePaneShown=0, PinCursor="Cursor Movable", TimePerDiv="1 s / Div", TimeStampFormat="Time", DataGraphDrawAsPoints=0, DataGraphLegendShown=1, DataGraphUniformSampleSpacing=0, DataGraphLegendPosition="0;0", DataGraphShowNamesAtCursor=0, PowerGraphDrawAsPoints=0, PowerGraphLegendShown=0, PowerGraphAvgFilterTime=Off, PowerGraphAvgFilterLen=Off, PowerGraphUniformSampleSpacing=0, PowerGraphLegendPosition="601;0", CodeGraphLegendShown=0, CodeGraphLegendPosition="608;0"
OpenWindow="Console", DockArea=BOTTOM, x=1, y=0, w=128, h=328, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Source Files", DockArea=LEFT, x=0, y=0, w=735, h=459, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Disassembly", DockArea=RIGHT, x=0, y=1, w=1150, h=319, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Memory 1", DockArea=BOTTOM, x=3, y=0, w=552, h=384, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, EditorAddress=0x30A3D70C
OpenWindow="Watched Data 1", DockArea=LEFT, x=0, y=1, w=735, h=577, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Terminal", DockArea=BOTTOM, x=0, y=0, w=473, h=384, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
OpenWindow="Data Sampling", DockArea=BOTTOM, x=2, y=0, w=1294, h=384, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, VisibleTab=0, UniformSampleSpacing=0
OpenWindow="Timeline", DockArea=RIGHT, x=0, y=0, w=1150, h=717, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=1, DataPaneShown=1, PowerPaneShown=0, CodePaneShown=0, PinCursor="Cursor Movable", TimePerDiv="2 s / Div", TimeStampFormat="Time", DataGraphDrawAsPoints=0, DataGraphLegendShown=1, DataGraphUniformSampleSpacing=0, DataGraphLegendPosition="0;502", DataGraphShowNamesAtCursor=0, PowerGraphDrawAsPoints=0, PowerGraphLegendShown=0, PowerGraphAvgFilterTime=Off, PowerGraphAvgFilterLen=Off, PowerGraphUniformSampleSpacing=0, PowerGraphLegendPosition="923;-69", CodeGraphLegendShown=0, CodeGraphLegendPosition="939;0"
OpenWindow="Console", DockArea=BOTTOM, x=1, y=0, w=238, h=384, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
SmartViewPlugin="", Page="", Toolbar="Hidden", Window="SmartView 1"
TableHeader="Source Files", SortCol="File", SortOrder="ASCENDING", VisibleCols=["File";"Status";"Size";"#Insts";"Path"], ColWidths=[263;100;100;100;950]
TableHeader="Data Sampling Table", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time"], ColWidths=[100;100]
TableHeader="Data Sampling Setup", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Type";"Value";"Min";"Max";"Average";"# Changes";"Min. Change";"Max. Change"], ColWidths=[438;100;100;100;100;100;110;126;126]
TableHeader="Data Sampling Table", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time";" (((motor_lf)->motor_controller).speed_PID).Measure";" (((motor_lf)->motor_controller).speed_PID).Ref"], ColWidths=[100;100;100;100]
TableHeader="Data Sampling Setup", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Type";"Value";"Min";"Max";"Average";"# Changes";"Min. Change";"Max. Change"], ColWidths=[438;100;114;124;114;124;110;126;126]
TableHeader="Power Sampling", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time";"Ch 0"], ColWidths=[100;100;100]
TableHeader="Task List", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Name";"Run Count";"Priority";"Status";"Timeout";"Stack Info";"ID";"Mutex Count";"Notified Value";"Notify State"], ColWidths=[110;110;110;110;110;110;110;110;110;110]
TableHeader="Watched Data 1", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Value";"Location";"Refresh"], ColWidths=[238;100;104;114]
TableHeader="Watched Data 1", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Value";"Location";"Refresh"], ColWidths=[238;149;104;218]
TableHeader="RegisterSelectionDialog", SortCol="None", SortOrder="ASCENDING", VisibleCols=[], ColWidths=[]
TableHeader="TargetExceptionDialog", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Address";"Description"], ColWidths=[27;27;27;26]
WatchedExpression="yaw_motor", RefreshRate=2, Window=Watched Data 1
WatchedExpression="pitch_motor", RefreshRate=2, Window=Watched Data 1
WatchedExpression="motor_rf", RefreshRate=2, Window=Watched Data 1
WatchedExpression="motor_lf", RefreshRate=2, Window=Watched Data 1
WatchedExpression="motor_lb", RefreshRate=2, Window=Watched Data 1
WatchedExpression="motor_rb", RefreshRate=2, Window=Watched Data 1
WatchedExpression="referee_data", RefreshRate=2, Window=Watched Data 1
WatchedExpression="referee_recv_info", Window=Watched Data 1
WatchedExpression="chassis_power_limit", Window=Watched Data 1
WatchedExpression="chassis_cmd_recv", RefreshRate=2, Window=Watched Data 1
WatchedExpression="vx_filter", RefreshRate=2, Window=Watched Data 1
WatchedExpression="loader", RefreshRate=2, Window=Watched Data 1
WatchedExpression="shoot.c::shoot_cmd_recv", RefreshRate=2, Window=Watched Data 1
WatchedExpression="loader", RefreshRate=2, Window=Watched Data 1
WatchedExpression="cap", RefreshRate=2, Window=Watched Data 1
WatchedExpression="shoot_cmd_recv", RefreshRate=5, Window=Watched Data 1