移植主框架(DM驱动),pitch用dm,灯条用外部单片机控制
This commit is contained in:
parent
b143ae73da
commit
7f3510c085
|
@ -54,8 +54,8 @@ include_directories(Inc Drivers/STM32F4xx_HAL_Driver/Inc Drivers/STM32F4xx_HAL_D
|
|||
modules modules/alarm modules/algorithm modules/BMI088 modules/can_comm modules/daemon modules/encoder modules/imu modules/ist8310
|
||||
modules/led modules/master_machine modules/message_center modules/motor modules/oled modules/referee modules/remote modules/RGB modules/standard_cmd
|
||||
modules/super_cap modules/TFminiPlus modules/unicomm modules/vofa modules/auto_aim
|
||||
modules/motor/DJImotor modules/motor/HTmotor modules/motor/LKmotor modules/motor/servo_motor modules/motor/step_motor modules/motor/ECmotor modules/motor/DMmotor
|
||||
application application/chassis application/cmd application/gimbal application/shoot
|
||||
modules/motor/DJImotor modules/motor/HTmotor modules/motor/LKmotor modules/motor/pwmmotor modules/motor/servo_motor modules/motor/step_motor modules/motor/ECmotor modules/motor/DMmotor
|
||||
application application/cmd application/gimbal application/shoot
|
||||
Middlewares/Third_Party/SEGGER/RTT Middlewares/Third_Party/SEGGER/Config)
|
||||
|
||||
include_directories(Middlewares/ST/ARM/DSP/Inc)
|
||||
|
|
|
@ -270,8 +270,8 @@ void MX_TIM8_Init(void)
|
|||
{
|
||||
Error_Handler();
|
||||
}
|
||||
sConfigOC.OCMode = TIM_OCMODE_TIMING;
|
||||
sConfigOC.Pulse = 0;
|
||||
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
||||
sConfigOC.Pulse = 2000;
|
||||
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
||||
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
|
||||
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
||||
|
|
|
@ -1,368 +0,0 @@
|
|||
/**
|
||||
* @file chassis.c
|
||||
* @author NeoZeng neozng1@hnu.edu.cn
|
||||
* @brief 底盘应用,负责接收robot_cmd的控制命令并根据命令进行运动学解算,得到输出
|
||||
* 注意底盘采取右手系,对于平面视图,底盘纵向运动的正前方为x正方向;横向运动的右侧为y正方向
|
||||
*
|
||||
* @version 0.1
|
||||
* @date 2022-12-04
|
||||
*
|
||||
* @copyright Copyright (c) 2022
|
||||
*
|
||||
*/
|
||||
|
||||
#include "chassis.h"
|
||||
#include "robot_def.h"
|
||||
#include "dji_motor.h"
|
||||
#include "super_cap.h"
|
||||
#include "message_center.h"
|
||||
#include "referee_task.h"
|
||||
|
||||
#include "general_def.h"
|
||||
#include "bsp_dwt.h"
|
||||
#include "referee_UI.h"
|
||||
#include "arm_math.h"
|
||||
#include "user_lib.h"
|
||||
|
||||
#include "vofa.h"
|
||||
|
||||
/* 根据robot_def.h中的macro自动计算的参数 */
|
||||
#define HALF_WHEEL_BASE (WHEEL_BASE / 2.0f) // 半轴距
|
||||
#define HALF_TRACK_WIDTH (TRACK_WIDTH / 2.0f) // 半轮距
|
||||
#define PERIMETER_WHEEL (RADIUS_WHEEL * 2 * PI) // 轮子周长
|
||||
|
||||
#define P_MAX 50.0f//功率控制 单位:W
|
||||
|
||||
/* 底盘应用包含的模块和信息存储,底盘是单例模式,因此不需要为底盘建立单独的结构体 */
|
||||
#ifdef CHASSIS_BOARD // 如果是底盘板,使用板载IMU获取底盘转动角速度
|
||||
#include "can_comm.h"
|
||||
#include "ins_task.h"
|
||||
static CANCommInstance *chasiss_can_comm; // 双板通信CAN comm
|
||||
attitude_t *Chassis_IMU_data;
|
||||
#endif // CHASSIS_BOARD
|
||||
#ifdef ONE_BOARD
|
||||
static Publisher_t *chassis_pub; // 用于发布底盘的数据
|
||||
static Subscriber_t *chassis_sub; // 用于订阅底盘的控制命令
|
||||
#endif // !ONE_BOARD
|
||||
static Chassis_Ctrl_Cmd_s chassis_cmd_recv; // 底盘接收到的控制命令
|
||||
static Chassis_Upload_Data_s chassis_feedback_data; // 底盘回传的反馈数据
|
||||
static Chassis_Ctrl_Cmd_s Chassis_Power_Mx;
|
||||
const static float CHASSIS_ACCEL_X_NUM=0.1f;
|
||||
const static float CHASSIS_ACCEL_Y_NUM=0.1f;
|
||||
|
||||
// 超级电容
|
||||
SuperCapInstance *cap; // 超级电容全局
|
||||
static uint16_t last_chassis_power_limit=0;//超级电容更新
|
||||
static DJIMotorInstance *motor_lf, *motor_rf, *motor_lb, *motor_rb; // left right forward back
|
||||
|
||||
/* 用于自旋变速策略的时间变量 */
|
||||
// static float t;
|
||||
|
||||
/* 私有函数计算的中介变量,设为静态避免参数传递的开销 */
|
||||
static float chassis_vx, chassis_vy; // 将云台系的速度投影到底盘
|
||||
static float vt_lf, vt_rf, vt_lb, vt_rb; // 底盘速度解算后的临时输出,待进行限幅
|
||||
first_order_filter_type_t vx_filter;
|
||||
first_order_filter_type_t vy_filter;
|
||||
static float P_cmd;
|
||||
|
||||
|
||||
void ChassisInit() {
|
||||
// 四个轮子的参数一样,改tx_id和反转标志位即可
|
||||
Motor_Init_Config_s chassis_motor_config = {
|
||||
.can_init_config.can_handle = &hcan1,
|
||||
.controller_param_init_config = {
|
||||
.speed_PID = {
|
||||
.Kp = 5.0f,
|
||||
.Ki = 0.01f,
|
||||
.Kd = 0.002f,
|
||||
.IntegralLimit = 3000,
|
||||
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit | PID_Derivative_On_Measurement,
|
||||
.MaxOut = 30000,
|
||||
},
|
||||
.current_PID = {
|
||||
.Kp = 0.0f,
|
||||
.Ki = 0.0f,
|
||||
.Kd = 0.0f,
|
||||
.IntegralLimit = 3000,
|
||||
.Improve = PID_Trapezoid_Intergral | PID_Integral_Limit | PID_Derivative_On_Measurement,
|
||||
.MaxOut = 15000,
|
||||
},
|
||||
},
|
||||
.controller_setting_init_config = {
|
||||
.angle_feedback_source = MOTOR_FEED,
|
||||
.speed_feedback_source = MOTOR_FEED,
|
||||
.outer_loop_type = SPEED_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 = 3;
|
||||
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
|
||||
motor_lf = 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_REVERSE;
|
||||
motor_rf = 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_REVERSE;
|
||||
motor_lb = DJIMotorInit(&chassis_motor_config);
|
||||
|
||||
chassis_motor_config.can_init_config.tx_id = 1;
|
||||
chassis_motor_config.controller_setting_init_config.motor_reverse_flag = MOTOR_DIRECTION_REVERSE;
|
||||
motor_rb = DJIMotorInit(&chassis_motor_config);
|
||||
|
||||
//超级电容
|
||||
SuperCap_Init_Config_s cap_conf = {
|
||||
.can_config = {
|
||||
.can_handle = &hcan1,
|
||||
.tx_id = 0x210,
|
||||
.rx_id = 0x211,
|
||||
|
||||
},
|
||||
.buffer_config_pid = {
|
||||
.Kp = 1.0f,
|
||||
.Ki = 0,
|
||||
.Kd = 0,
|
||||
.MaxOut = 300,
|
||||
},
|
||||
};
|
||||
cap = SuperCapInit(&cap_conf); // 超级电容初始化
|
||||
|
||||
//用一阶滤波代替斜波函数生成 //增大更能刹住
|
||||
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
|
||||
Chassis_IMU_data = INS_Init(); // 底盘IMU初始化
|
||||
|
||||
CANComm_Init_Config_s comm_conf = {
|
||||
.can_config = {
|
||||
.can_handle = &hcan2,
|
||||
.tx_id = 0x311,
|
||||
.rx_id = 0x312,
|
||||
},
|
||||
.recv_data_len = sizeof(Chassis_Ctrl_Cmd_s),
|
||||
.send_data_len = sizeof(Chassis_Upload_Data_s),
|
||||
};
|
||||
chasiss_can_comm = CANCommInit(&comm_conf); // can comm初始化
|
||||
#endif // CHASSIS_BOARD
|
||||
|
||||
#ifdef ONE_BOARD // 单板控制整车,则通过pubsub来传递消息
|
||||
chassis_sub = SubRegister("chassis_cmd", sizeof(Chassis_Ctrl_Cmd_s));
|
||||
chassis_pub = PubRegister("chassis_feed", sizeof(Chassis_Upload_Data_s));
|
||||
#endif // ONE_BOARD
|
||||
}
|
||||
|
||||
#define LF_CENTER ((HALF_TRACK_WIDTH + CENTER_GIMBAL_OFFSET_X + HALF_WHEEL_BASE - CENTER_GIMBAL_OFFSET_Y) * DEGREE_2_RAD)
|
||||
#define RF_CENTER ((HALF_TRACK_WIDTH - CENTER_GIMBAL_OFFSET_X + HALF_WHEEL_BASE - CENTER_GIMBAL_OFFSET_Y) * DEGREE_2_RAD)
|
||||
#define LB_CENTER ((HALF_TRACK_WIDTH + CENTER_GIMBAL_OFFSET_X + HALF_WHEEL_BASE + CENTER_GIMBAL_OFFSET_Y) * DEGREE_2_RAD)
|
||||
#define RB_CENTER ((HALF_TRACK_WIDTH - CENTER_GIMBAL_OFFSET_X + HALF_WHEEL_BASE + CENTER_GIMBAL_OFFSET_Y) * DEGREE_2_RAD)
|
||||
/**
|
||||
* @brief 计算每个轮毂电机的输出,正运动学解算
|
||||
* 用宏进行预替换减小开销,运动解算具体过程参考教程
|
||||
*/
|
||||
//全向轮解算
|
||||
static void OmniCalculate() {
|
||||
vt_rf = HALF_WHEEL_BASE * chassis_cmd_recv.wz + chassis_vx * 0.707f + chassis_vy * 0.707f;
|
||||
vt_rb = HALF_WHEEL_BASE * chassis_cmd_recv.wz + chassis_vx * 0.707f - chassis_vy * 0.707f;
|
||||
vt_lb = HALF_WHEEL_BASE * chassis_cmd_recv.wz - chassis_vx * 0.707f - chassis_vy * 0.707f;
|
||||
vt_lf = HALF_WHEEL_BASE * chassis_cmd_recv.wz - chassis_vx * 0.707f + chassis_vy * 0.707f;
|
||||
|
||||
vt_rf = (vt_rf / RADIUS_WHEEL) * 180 / PI * REDUCTION_RATIO_WHEEL;
|
||||
vt_rb = (vt_rb / RADIUS_WHEEL) * 180 / PI * REDUCTION_RATIO_WHEEL;
|
||||
vt_lb = (vt_lb / RADIUS_WHEEL) * 180 / PI * REDUCTION_RATIO_WHEEL;
|
||||
vt_lf = (vt_lf / RADIUS_WHEEL) * 180 / PI * REDUCTION_RATIO_WHEEL;
|
||||
}
|
||||
|
||||
static const float motor_power_K[3] = {1.6301e-6f,5.7501e-7f,2.5863e-7f};
|
||||
float input;
|
||||
|
||||
float P_max = 0;
|
||||
|
||||
///依据3508电机功率模型,预测电机输出功率
|
||||
static float EstimatePower(DJIMotorInstance* chassis_motor)
|
||||
{
|
||||
|
||||
float I_cmd = chassis_motor->motor_controller.current_PID.Output;
|
||||
float w = chassis_motor->measure.speed_aps /6 ;//aps to rpm
|
||||
|
||||
float power = motor_power_K[0] * I_cmd * w + motor_power_K[1]*w*w + motor_power_K[2]*I_cmd*I_cmd;
|
||||
|
||||
return power;
|
||||
}
|
||||
/**
|
||||
* @brief 根据裁判系统和电容剩余容量对输出进行限制并设置电机参考值
|
||||
*
|
||||
*/
|
||||
static void LimitChassisOutput()
|
||||
{
|
||||
// float Plimit = 1.0f;
|
||||
P_cmd = motor_rf->motor_controller.motor_power_predict +
|
||||
motor_rb->motor_controller.motor_power_predict +
|
||||
motor_lb->motor_controller.motor_power_predict +
|
||||
motor_lf->motor_controller.motor_power_predict + 3.6f;
|
||||
|
||||
// if(chassis_cmd_recv.buffer_energy<50&&chassis_cmd_recv.buffer_energy>=40) Plimit=0.9f;
|
||||
// else if(chassis_cmd_recv.buffer_energy<40&&chassis_cmd_recv.buffer_energy>=35) Plimit=0.75f;
|
||||
// else if(chassis_cmd_recv.buffer_energy<35&&chassis_cmd_recv.buffer_energy>=30) Plimit=0.5f;
|
||||
// else if(chassis_cmd_recv.buffer_energy<30&&chassis_cmd_recv.buffer_energy>=20) Plimit=0.25f;
|
||||
// else if(chassis_cmd_recv.buffer_energy<20&&chassis_cmd_recv.buffer_energy>=10) Plimit=0.125f;
|
||||
// else if(chassis_cmd_recv.buffer_energy<10&&chassis_cmd_recv.buffer_energy>=0) Plimit=0.05f;
|
||||
// else if(chassis_cmd_recv.buffer_energy==60) Plimit=1.0f;
|
||||
|
||||
if (cap->cap_msg.cap_vol>1800)
|
||||
{
|
||||
P_max = input + chassis_cmd_recv.buffer_supercap ;
|
||||
}
|
||||
else
|
||||
{
|
||||
P_max = input;
|
||||
}
|
||||
float K = P_max / P_cmd;
|
||||
|
||||
motor_rf->motor_controller.motor_power_scale = K;
|
||||
motor_rb->motor_controller.motor_power_scale = K;
|
||||
motor_lf->motor_controller.motor_power_scale = K;
|
||||
motor_lb->motor_controller.motor_power_scale = K;
|
||||
|
||||
{
|
||||
DJIMotorSetRef(motor_lf, vt_lf);
|
||||
DJIMotorSetRef(motor_rf, vt_rf);
|
||||
DJIMotorSetRef(motor_lb, vt_lb);
|
||||
DJIMotorSetRef(motor_rb, vt_rb);
|
||||
}
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief 超电功率对缓冲功率进行闭环
|
||||
*
|
||||
*
|
||||
*/
|
||||
static void SuperCapSetUpdate()
|
||||
{
|
||||
|
||||
PIDCalculate(&cap->buffer_pid, chassis_cmd_recv.buffer_energy,15);//对缓冲功率进行闭环
|
||||
input = chassis_cmd_recv.chassis_power_limit - cap->buffer_pid.Output;
|
||||
LIMIT_MIN_MAX(input, 30, 130);
|
||||
SuperCapSetPower(cap,input);
|
||||
|
||||
}
|
||||
/**
|
||||
* @brief 根据每个轮子的速度反馈,计算底盘的实际运动速度,逆运动解算
|
||||
* 对于双板的情况,考虑增加来自底盘板IMU的数据
|
||||
*
|
||||
*/
|
||||
static void EstimateSpeed() {
|
||||
// 根据电机速度和陀螺仪的角速度进行解算,还可以利用加速度计判断是否打滑(如果有)
|
||||
// chassis_feedback_data.vx vy wz =
|
||||
// ...
|
||||
}
|
||||
static chassis_mode_e last_chassis_mode;
|
||||
static float rotate_speed = 70000;
|
||||
/* 机器人底盘控制核心任务 */
|
||||
void ChassisTask() {
|
||||
// 后续增加没收到消息的处理(双板的情况)
|
||||
// 获取新的控制信息
|
||||
#ifdef ONE_BOARD
|
||||
SubGetMessage(chassis_sub, &chassis_cmd_recv);
|
||||
#endif
|
||||
#ifdef CHASSIS_BOARD
|
||||
chassis_cmd_recv = *(Chassis_Ctrl_Cmd_s *)CANCommGet(chasiss_can_comm);
|
||||
#endif // CHASSIS_BOARD
|
||||
|
||||
if (chassis_cmd_recv.chassis_mode == CHASSIS_ZERO_FORCE) { // 如果出现重要模块离线或遥控器设置为急停,让电机停止
|
||||
DJIMotorStop(motor_lf);
|
||||
DJIMotorStop(motor_rf);
|
||||
DJIMotorStop(motor_lb);
|
||||
DJIMotorStop(motor_rb);
|
||||
} else { // 正常工作
|
||||
DJIMotorEnable(motor_lf);
|
||||
DJIMotorEnable(motor_rf);
|
||||
DJIMotorEnable(motor_lb);
|
||||
DJIMotorEnable(motor_rb);
|
||||
}
|
||||
|
||||
// 根据控制模式设定旋转速度
|
||||
switch (chassis_cmd_recv.chassis_mode) {
|
||||
case CHASSIS_NO_FOLLOW: // 底盘不旋转,但维持全向机动,一般用于调整云台姿态
|
||||
chassis_cmd_recv.wz = 0;
|
||||
break;
|
||||
case CHASSIS_FOLLOW_GIMBAL_YAW: // 跟随云台,不单独设置pid,以误差角度平方为速度输出
|
||||
chassis_cmd_recv.wz = 40.0f * chassis_cmd_recv.offset_angle * abs(chassis_cmd_recv.offset_angle);
|
||||
LIMIT_MIN_MAX(chassis_cmd_recv.wz,-35000,35000);
|
||||
break;
|
||||
case CHASSIS_SIDEWAYS: // 侧向,不单独设置pid,以误差角度平方为速度输出
|
||||
chassis_cmd_recv.wz = 20.0f * (chassis_cmd_recv.offset_angle - 45)* abs(chassis_cmd_recv.offset_angle - 45);
|
||||
LIMIT_MIN_MAX(chassis_cmd_recv.wz,-35000,35000);
|
||||
break;
|
||||
case CHASSIS_ROTATE: // 自旋,同时保持全向机动;当前wz维持定值,后续增加不规则的变速策略
|
||||
if(last_chassis_mode != CHASSIS_ROTATE){
|
||||
rotate_speed = -rotate_speed;
|
||||
}
|
||||
chassis_cmd_recv.wz = rotate_speed;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
last_chassis_mode = chassis_cmd_recv.chassis_mode;
|
||||
// 根据云台和底盘的角度offset将控制量映射到底盘坐标系上
|
||||
// 底盘逆时针旋转为角度正方向;云台命令的方向以云台指向的方向为x,采用右手系(x指向正北时y在正东)
|
||||
static float sin_theta, cos_theta;
|
||||
cos_theta = arm_cos_f32(chassis_cmd_recv.offset_angle * DEGREE_2_RAD);
|
||||
sin_theta = arm_sin_f32(chassis_cmd_recv.offset_angle * DEGREE_2_RAD);
|
||||
|
||||
//一阶低通滤波计算
|
||||
first_order_filter_cali(&vx_filter, chassis_cmd_recv.vx);
|
||||
first_order_filter_cali(&vy_filter, chassis_cmd_recv.vy);
|
||||
|
||||
chassis_cmd_recv.vx = vx_filter.out;
|
||||
chassis_cmd_recv.vy = vy_filter.out;
|
||||
|
||||
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);
|
||||
|
||||
|
||||
// 根据控制模式进行正运动学解算,计算底盘输出
|
||||
//MecanumCalculate();
|
||||
OmniCalculate();
|
||||
////对缓冲功率进行闭环
|
||||
SuperCapSetUpdate();
|
||||
// 根据裁判系统的反馈数据和电容数据对输出限幅并设定闭环参考值
|
||||
LimitChassisOutput();
|
||||
|
||||
// float vofa_send_data[2];
|
||||
// vofa_send_data[0] = motor_lb->motor_controller.speed_PID.Ref;
|
||||
// vofa_send_data[1] = motor_lb->motor_controller.speed_PID.Measure;
|
||||
// vofa_justfloat_output(vofa_send_data, 8, &huart1);
|
||||
|
||||
// 根据电机的反馈速度和IMU(如果有)计算真实速度
|
||||
EstimateSpeed();
|
||||
|
||||
//todo: 裁判系统信息移植到消息中心发送
|
||||
// 获取裁判系统数据 建议将裁判系统与底盘分离,所以此处数据应使用消息中心发送
|
||||
// 发送敌方方颜色id
|
||||
//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.cap_vol = cap->cap_msg.cap_vol;
|
||||
|
||||
// 推送反馈消息
|
||||
#ifdef ONE_BOARD
|
||||
PubPushMessage(chassis_pub, (void *) &chassis_feedback_data);
|
||||
#endif
|
||||
#ifdef CHASSIS_BOARD
|
||||
CANCommSend(chasiss_can_comm, (void *)&chassis_feedback_data);
|
||||
#endif // CHASSIS_BOARD
|
||||
}
|
|
@ -1,16 +0,0 @@
|
|||
#ifndef CHASSIS_H
|
||||
#define CHASSIS_H
|
||||
|
||||
/**
|
||||
* @brief 底盘应用初始化,请在开启rtos之前调用(目前会被RobotInit()调用)
|
||||
*
|
||||
*/
|
||||
void ChassisInit();
|
||||
|
||||
/**
|
||||
* @brief 底盘应用任务,放入实时系统以一定频率运行
|
||||
*
|
||||
*/
|
||||
void ChassisTask();
|
||||
|
||||
#endif // CHASSIS_H
|
|
@ -1,24 +0,0 @@
|
|||
# chassis
|
||||
|
||||
|
||||
|
||||
## 工作流程
|
||||
|
||||
首先进行初始化,`ChasissInit()`会被`RobotInit()`调用,进行裁判系统、底盘电机的初始化。如果为双板模式,则还会初始化IMU,并且将消息订阅者和发布者的初始化改为`CANComm`的初始化。
|
||||
|
||||
操作系统启动后,工作顺序为:
|
||||
|
||||
1. 从cmd模块获取数据(如果双板则从CANComm获取)
|
||||
2. 判断当前控制数据的模式,如果为停止则停止所有电机
|
||||
3. 根据控制数据,计算底盘的旋转速度
|
||||
4. 根据控制数据中yaw电机的编码器值`angle_offset`,将控制数据映射到底盘坐标系下
|
||||
5. 进行麦克纳姆轮的运动学解算,得到每个电机的设定值
|
||||
6. 获取裁判系统的数据,并根据底盘功率限制对输出进行限幅
|
||||
7. 由电机的反馈数据和IMU(如果有),计算底盘当前的真实运动速度
|
||||
8. 设置底盘反馈数据,包括运动速度和裁判系统数据
|
||||
9. 将反馈数据推送到消息中心(如果双板则通过CANComm发送)
|
||||
|
||||
|
||||
### 后续支持平衡底盘
|
||||
|
||||
新增一个app balance_chassis
|
|
@ -79,22 +79,6 @@ void RobotCMDInit() {
|
|||
shoot_cmd_pub = PubRegister("shoot_cmd", sizeof(Shoot_Ctrl_Cmd_s));
|
||||
shoot_feed_sub = SubRegister("shoot_feed", sizeof(Shoot_Upload_Data_s));
|
||||
|
||||
#ifdef ONE_BOARD // 双板兼容
|
||||
chassis_cmd_pub = PubRegister("chassis_cmd", sizeof(Chassis_Ctrl_Cmd_s));
|
||||
chassis_feed_sub = SubRegister("chassis_feed", sizeof(Chassis_Upload_Data_s));
|
||||
#endif // ONE_BOARD
|
||||
#ifdef GIMBAL_BOARD
|
||||
CANComm_Init_Config_s comm_conf = {
|
||||
.can_config = {
|
||||
.can_handle = &hcan1,
|
||||
.tx_id = 0x312,
|
||||
.rx_id = 0x311,
|
||||
},
|
||||
.recv_data_len = sizeof(Chassis_Upload_Data_s),
|
||||
.send_data_len = sizeof(Chassis_Ctrl_Cmd_s),
|
||||
};
|
||||
cmd_can_comm = CANCommInit(&comm_conf);
|
||||
#endif // GIMBAL_BOARD
|
||||
gimbal_cmd_send.pitch = 0;
|
||||
|
||||
robot_state = ROBOT_READY; // 启动时机器人进入工作模式,后续加入所有应用初始化完成之后再进入
|
||||
|
@ -126,15 +110,6 @@ static void CalcOffsetAngle() {
|
|||
#endif
|
||||
}
|
||||
|
||||
//功能:死亡后清除小陀螺的状态
|
||||
static void death_check() {
|
||||
if (referee_data->GameRobotState.current_HP <= 0 ||
|
||||
referee_data->GameRobotState.power_management_chassis_output == 0) {
|
||||
rc_data[TEMP].key_count[KEY_PRESS][Key_E] = 0;
|
||||
gimbal_cmd_send.yaw = gimbal_fetch_data.gimbal_imu_data.YawTotalAngle;
|
||||
}
|
||||
}
|
||||
|
||||
//功能:等级提升弹频提高
|
||||
static void shoot_rate_improve() {
|
||||
if (referee_data->GameRobotState.robot_level < 5)
|
||||
|
@ -373,26 +348,6 @@ static void MouseKeySet() {
|
|||
shoot_cmd_send.friction_mode = FRICTION_ON;
|
||||
break;
|
||||
}
|
||||
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_B] % 2) // B键开关弹舱盖
|
||||
{
|
||||
case 0:
|
||||
shoot_cmd_send.lid_mode = LID_CLOSE;
|
||||
break;
|
||||
default:
|
||||
shoot_cmd_send.lid_mode = LID_OPEN;
|
||||
break;
|
||||
}
|
||||
// switch (rc_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_Q] % 2) // Q键开关热控
|
||||
{
|
||||
case 0:
|
||||
|
@ -402,25 +357,6 @@ static void MouseKeySet() {
|
|||
shoot_cmd_send.heat_mode = HEAT_CLOSE;
|
||||
break;
|
||||
}
|
||||
switch (rc_data[TEMP].key_count[KEY_PRESS][Key_C] % 2) // C键侧向
|
||||
{
|
||||
case 0:
|
||||
switch (rc_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;
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
chassis_cmd_send.chassis_mode = CHASSIS_SIDEWAYS;
|
||||
break;
|
||||
}
|
||||
// switch (rc_data[TEMP].key_count[KEY_PRESS][Key_G] % 3) // G键切换发射模式
|
||||
// {
|
||||
// case 0:
|
||||
|
@ -433,23 +369,12 @@ static void MouseKeySet() {
|
|||
// loader_flag = 3;
|
||||
// break;
|
||||
// }
|
||||
switch (rc_data[TEMP].key[KEY_PRESS].shift) //按shift允许消耗超级电容能量
|
||||
{
|
||||
case 0:
|
||||
chassis_cmd_send.buffer_supercap = 5;
|
||||
break;
|
||||
case 1:
|
||||
chassis_cmd_send.buffer_supercap = 200;
|
||||
chassis_cmd_send.vx = rc_data[TEMP].key[KEY_PRESS].a * 15000 - rc_data[TEMP].key[KEY_PRESS].d * 15000;
|
||||
break;
|
||||
}
|
||||
|
||||
shoot_rate_improve();
|
||||
|
||||
if (shoot_fetch_data.stalled_flag == 1)
|
||||
shoot_cmd_send.loader_mode = LOAD_REVERSE;
|
||||
|
||||
death_check();
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -525,45 +450,6 @@ static void VTMouseKeySet() {
|
|||
shoot_cmd_send.friction_mode = FRICTION_ON;
|
||||
break;
|
||||
}
|
||||
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_B] % 2) // B键开关弹舱盖
|
||||
{
|
||||
case 0:
|
||||
shoot_cmd_send.lid_mode = LID_CLOSE;
|
||||
break;
|
||||
default:
|
||||
shoot_cmd_send.lid_mode = LID_OPEN;
|
||||
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 (vt_data[TEMP].key_count[KEY_PRESS][Key_C] % 2) // C键侧向
|
||||
{
|
||||
case 0:
|
||||
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;
|
||||
}
|
||||
break;
|
||||
case 1:
|
||||
chassis_cmd_send.chassis_mode = CHASSIS_SIDEWAYS;
|
||||
break;
|
||||
}
|
||||
switch (vt_data[TEMP].key_count[KEY_PRESS][Key_Q] % 2) // Q键开关热控
|
||||
{
|
||||
case 0:
|
||||
|
@ -585,23 +471,11 @@ static void VTMouseKeySet() {
|
|||
// loader_flag = 3;
|
||||
// break;
|
||||
// }
|
||||
switch (vt_data[TEMP].key[KEY_PRESS].shift) //按shift允许消耗超级电容能量
|
||||
{
|
||||
case 0:
|
||||
chassis_cmd_send.buffer_supercap = 5;
|
||||
break;
|
||||
case 1:
|
||||
chassis_cmd_send.buffer_supercap = 200;
|
||||
chassis_cmd_send.vx = rc_data[TEMP].key[KEY_PRESS].a * 1 - rc_data[TEMP].key[KEY_PRESS].d * 1;
|
||||
break;
|
||||
}
|
||||
|
||||
shoot_rate_improve();
|
||||
|
||||
if (shoot_fetch_data.stalled_flag == 1)
|
||||
shoot_cmd_send.loader_mode = LOAD_REVERSE;
|
||||
|
||||
death_check();
|
||||
}
|
||||
|
||||
|
||||
|
@ -616,11 +490,11 @@ static void EmergencyHandler() {
|
|||
// 拨轮的向下拨超过一半进入急停模式.注意向打时下拨轮是正
|
||||
if (rc_data[TEMP].rc.dial > 300 || robot_state == ROBOT_STOP) // 还需添加重要应用和模块离线的判断
|
||||
{
|
||||
robot_state = ROBOT_STOP;
|
||||
robot_state = ROBOT_READY;
|
||||
gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE;
|
||||
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.shoot_mode = SHOOT_ON;
|
||||
shoot_cmd_send.friction_mode = FRICTION_ON;
|
||||
shoot_cmd_send.loader_mode = LOAD_STOP;
|
||||
LOGERROR("[CMD] emergency stop!");
|
||||
}
|
||||
|
@ -679,11 +553,9 @@ void RobotCMDTask() {
|
|||
if (referee_data->GameRobotState.power_management_gimbal_output == 0) {
|
||||
gimbal_cmd_send.gimbal_mode = GIMBAL_ZERO_FORCE;
|
||||
}
|
||||
if (referee_data->GameRobotState.power_management_shooter_output == 0) {
|
||||
shoot_cmd_send.shoot_mode = SHOOT_OFF;
|
||||
}
|
||||
|
||||
death_check();
|
||||
// if (referee_data->GameRobotState.power_management_shooter_output == 0) {
|
||||
// shoot_cmd_send.shoot_mode = SHOOT_ON;
|
||||
// }
|
||||
|
||||
// 推送消息,双板通信,视觉通信等
|
||||
// 其他应用所需的控制数据在remotecontrolsetmode和mousekeysetmode中完成设置
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#include "gimbal.h"
|
||||
#include "robot_def.h"
|
||||
#include "dji_motor.h"
|
||||
#include "dmmotor.h"
|
||||
#include "ins_task.h"
|
||||
#include "message_center.h"
|
||||
#include "general_def.h"
|
||||
|
@ -16,29 +17,6 @@ static Gimbal_Upload_Data_s gimbal_feedback_data; // 回传给cmd的云台状态
|
|||
static Gimbal_Ctrl_Cmd_s gimbal_cmd_recv; // 来自cmd的控制信息
|
||||
|
||||
static float gravity_current = 0;
|
||||
static void LimitPitchAngleAuto() {
|
||||
/** 注意电机角度与陀螺仪角度方向是否相同
|
||||
* 目前 add > 0, 向下转动
|
||||
* 电机角度值减小
|
||||
* 陀螺仪角度值增大
|
||||
**/
|
||||
float add;
|
||||
float angle_set;
|
||||
|
||||
add = gimbal_cmd_recv.pitch - gimba_IMU_data->Pitch;
|
||||
|
||||
if(pitch_motor->measure.angle_single_round - add > PITCH_MAX_RELATIVE_ANGLE){
|
||||
if(add < 0.0f ){
|
||||
add = PITCH_MAX_ANGLE - pitch_motor->measure.angle_single_round;
|
||||
}
|
||||
}else if(pitch_motor->measure.angle_single_round - add < PITCH_MIN_RELATIVE_ANGLE){
|
||||
if(add > 0.0f){
|
||||
add = PITCH_MIN_RELATIVE_ANGLE - pitch_motor->measure.angle_single_round;
|
||||
}
|
||||
}
|
||||
angle_set = gimba_IMU_data->Pitch;
|
||||
DJIMotorSetRef(pitch_motor, angle_set+add);
|
||||
}
|
||||
|
||||
void GimbalInit() {
|
||||
gimba_IMU_data = INS_Init(); // IMU先初始化,获取姿态数据指针赋给yaw电机的其他数据来源
|
||||
|
@ -85,6 +63,7 @@ void GimbalInit() {
|
|||
.can_init_config = {
|
||||
.can_handle = &hcan2,
|
||||
.tx_id = 1,
|
||||
.rx_id = 3,
|
||||
},
|
||||
.controller_param_init_config = {
|
||||
.angle_PID = {
|
||||
|
@ -117,7 +96,7 @@ void GimbalInit() {
|
|||
.feedforward_flag = CURRENT_FEEDFORWARD,
|
||||
.feedback_reverse_flag = FEEDBACK_DIRECTION_REVERSE
|
||||
},
|
||||
.motor_type = GM6020,
|
||||
.motor_type = DM4310,
|
||||
.motor_control_type = CURRENT_CONTROL
|
||||
};
|
||||
// 电机对total_angle闭环,上电时为零,会保持静止,收到遥控器数据再动
|
||||
|
|
|
@ -9,10 +9,6 @@
|
|||
#pragma message "check if you have configured the parameters in robot_def.h, IF NOT, please refer to the comments AND DO IT, otherwise the robot will have FATAL ERRORS!!!"
|
||||
#endif // !ROBOT_DEF_PARAM_WARNING
|
||||
|
||||
#if defined(ONE_BOARD) || defined(CHASSIS_BOARD)
|
||||
#include "chassis.h"
|
||||
#endif
|
||||
|
||||
#if defined(ONE_BOARD) || defined(GIMBAL_BOARD)
|
||||
#include "gimbal.h"
|
||||
#include "shoot.h"
|
||||
|
@ -36,10 +32,6 @@ void RobotInit()
|
|||
ShootInit();
|
||||
#endif
|
||||
|
||||
#if defined(ONE_BOARD) || defined(CHASSIS_BOARD)
|
||||
ChassisInit();
|
||||
#endif
|
||||
|
||||
OSTaskInit(); // 创建基础任务
|
||||
|
||||
// 初始化完成,开启中断
|
||||
|
@ -55,8 +47,4 @@ void RobotTask()
|
|||
ShootTask();
|
||||
#endif
|
||||
|
||||
#if defined(ONE_BOARD) || defined(CHASSIS_BOARD)
|
||||
ChassisTask();
|
||||
#endif
|
||||
|
||||
}
|
|
@ -6,10 +6,13 @@
|
|||
#include "bsp_dwt.h"
|
||||
#include "general_def.h"
|
||||
#include "servo_motor.h"
|
||||
#include "snail.h"
|
||||
#include "RGB.h"
|
||||
|
||||
/* 对于双发射机构的机器人,将下面的数据封装成结构体即可,生成两份shoot应用实例 */
|
||||
static DJIMotorInstance *friction_l, *friction_r, *loader; // 拨盘电机
|
||||
static ServoInstance *lid;
|
||||
static PwmmotorInstance *friction_l1, *friction_r1; // snail电机
|
||||
|
||||
static Publisher_t *shoot_pub;
|
||||
static Shoot_Ctrl_Cmd_s shoot_cmd_recv; // 来自cmd的发射控制信息
|
||||
|
@ -62,8 +65,8 @@ void ShootInit()
|
|||
// 拨盘电机
|
||||
Motor_Init_Config_s loader_config = {
|
||||
.can_init_config = {
|
||||
.can_handle = &hcan2,
|
||||
.tx_id = 1
|
||||
.can_handle = &hcan1,
|
||||
.tx_id = 2
|
||||
},
|
||||
.controller_param_init_config = {
|
||||
.angle_PID = {
|
||||
|
@ -105,14 +108,19 @@ void ShootInit()
|
|||
shoot_pub = PubRegister("shoot_feed", sizeof(Shoot_Upload_Data_s));
|
||||
shoot_sub = SubRegister("shoot_cmd", sizeof(Shoot_Ctrl_Cmd_s));
|
||||
|
||||
Servo_Init_Config_s lid_config = {
|
||||
.htim = &htim1,
|
||||
Pwmmotor_Init_Config_s friction_l1_config = {
|
||||
.htim = &htim8,
|
||||
.Channel = TIM_CHANNEL_1,
|
||||
.Servo_type = Servo180,
|
||||
.Servo_Angle_Type = Free_Angle_mode,
|
||||
.Pwmmotor_type = 0,
|
||||
};
|
||||
friction_l1 = PwmmotorInit(&friction_l1_config);
|
||||
|
||||
lid = ServoInit(&lid_config);
|
||||
Pwmmotor_Init_Config_s friction_r1_config = {
|
||||
.htim = &htim8,
|
||||
.Channel = TIM_CHANNEL_2,
|
||||
.Pwmmotor_type = 0,
|
||||
};
|
||||
friction_r1 = PwmmotorInit(&friction_r1_config);
|
||||
|
||||
// SPI_Init_Config_s rgb_config = {
|
||||
// .spi_handle = ;
|
||||
|
@ -153,39 +161,27 @@ 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()
|
||||
{
|
||||
//WS2812_Number_4(0x000018,0x000018,0x000018,0x000018);
|
||||
//从cmd获取控制数据
|
||||
SubGetMessage(shoot_sub, &shoot_cmd_recv);
|
||||
|
||||
// 对shoot mode等于SHOOT_STOP的情况特殊处理,直接停止所有电机(紧急停止)
|
||||
if (shoot_cmd_recv.shoot_mode == SHOOT_OFF)
|
||||
{
|
||||
DJIMotorSetRef(friction_l, 0);
|
||||
DJIMotorSetRef(friction_r, 0);
|
||||
DJIMotorStop(loader);
|
||||
//DJIMotorSetRef(friction_l, 0);
|
||||
//DJIMotorSetRef(friction_r, 0);
|
||||
DJIMotorEnable(loader);
|
||||
}
|
||||
else // 恢复运行
|
||||
{
|
||||
DJIMotorEnable(friction_l);
|
||||
DJIMotorEnable(friction_r);
|
||||
//DJIMotorEnable(friction_l);
|
||||
//DJIMotorEnable(friction_r);
|
||||
DJIMotorEnable(loader);
|
||||
}
|
||||
|
||||
DJIMotorEnable(loader);
|
||||
// 如果上一次触发单发或3发指令的时间加上不应期仍然大于当前时间(尚未休眠完毕),直接返回即可
|
||||
// 单发模式主要提供给能量机关激活使用(以及英雄的射击大部分处于单发)
|
||||
if (hibernate_time + dead_time > DWT_GetTimeline_ms())
|
||||
|
@ -256,44 +252,23 @@ void ShootTask()
|
|||
//default: // 当前为了调试设定的默认值4000,因为还没有加入裁判系统无法读取弹速.
|
||||
DJIMotorSetRef(friction_l, 39000);
|
||||
DJIMotorSetRef(friction_r, 39000);
|
||||
|
||||
// break;
|
||||
// }
|
||||
Pwm_MotorControl(friction_l1, 2000);
|
||||
Pwm_MotorControl(friction_r1, 2000);
|
||||
}
|
||||
else // 关闭摩擦轮
|
||||
{
|
||||
DJIMotorSetRef(friction_l, 0);
|
||||
DJIMotorSetRef(friction_r, 0);
|
||||
|
||||
Pwm_Motor_Stop(friction_l1, 1000);
|
||||
Pwm_Motor_Stop(friction_r1, 1000);
|
||||
}
|
||||
|
||||
// 开关弹舱盖
|
||||
if (shoot_cmd_recv.lid_mode == LID_CLOSE)
|
||||
{
|
||||
Servo_Motor_FreeAngle_Set(lid,115);// 小107 大115
|
||||
}
|
||||
else if (shoot_cmd_recv.lid_mode == LID_OPEN)
|
||||
{
|
||||
Servo_Motor_FreeAngle_Set(lid,10);
|
||||
}
|
||||
|
||||
// 开关热控
|
||||
if(shoot_cmd_recv.heat_mode == HEAT_OPEN)
|
||||
{
|
||||
if(shoot_cmd_recv.heat>=(0.85*shoot_cmd_recv.heat_limit))
|
||||
{
|
||||
DJIMotorStop(loader);
|
||||
}
|
||||
else
|
||||
{
|
||||
DJIMotorEnable(loader);
|
||||
}
|
||||
}
|
||||
else if(shoot_cmd_recv.heat_mode == HEAT_CLOSE) {
|
||||
DJIMotorEnable(loader);
|
||||
}
|
||||
//卡弹检测
|
||||
stalled_detect();
|
||||
// 热量控制
|
||||
//Heat_control();
|
||||
|
||||
// 反馈数据,目前暂时没有要设定的反馈数据,后续可能增加应用离线监测以及卡弹反馈
|
||||
PubPushMessage(shoot_pub, (void *)&shoot_feedback_data);
|
||||
|
|
File diff suppressed because one or more lines are too long
File diff suppressed because it is too large
Load Diff
|
@ -1,60 +0,0 @@
|
|||
{
|
||||
"configurations" :
|
||||
[
|
||||
{
|
||||
"directories" :
|
||||
[
|
||||
{
|
||||
"build" : ".",
|
||||
"jsonFile" : "directory-.-Debug-d0094a50bb2071803777.json",
|
||||
"minimumCMakeVersion" :
|
||||
{
|
||||
"string" : "3.25"
|
||||
},
|
||||
"projectIndex" : 0,
|
||||
"source" : ".",
|
||||
"targetIndexes" :
|
||||
[
|
||||
0
|
||||
]
|
||||
}
|
||||
],
|
||||
"name" : "Debug",
|
||||
"projects" :
|
||||
[
|
||||
{
|
||||
"directoryIndexes" :
|
||||
[
|
||||
0
|
||||
],
|
||||
"name" : "uav",
|
||||
"targetIndexes" :
|
||||
[
|
||||
0
|
||||
]
|
||||
}
|
||||
],
|
||||
"targets" :
|
||||
[
|
||||
{
|
||||
"directoryIndex" : 0,
|
||||
"id" : "uav.elf::@6890427a1f51a3e7e1df",
|
||||
"jsonFile" : "target-uav.elf-Debug-656e98db05d9df89452c.json",
|
||||
"name" : "uav.elf",
|
||||
"projectIndex" : 0
|
||||
}
|
||||
]
|
||||
}
|
||||
],
|
||||
"kind" : "codemodel",
|
||||
"paths" :
|
||||
{
|
||||
"build" : "D:/zhandui/cqdm/uav/cmake-build-debug",
|
||||
"source" : "D:/zhandui/cqdm/uav"
|
||||
},
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 5
|
||||
}
|
||||
}
|
|
@ -1,14 +0,0 @@
|
|||
{
|
||||
"backtraceGraph" :
|
||||
{
|
||||
"commands" : [],
|
||||
"files" : [],
|
||||
"nodes" : []
|
||||
},
|
||||
"installers" : [],
|
||||
"paths" :
|
||||
{
|
||||
"build" : ".",
|
||||
"source" : "."
|
||||
}
|
||||
}
|
|
@ -1,108 +0,0 @@
|
|||
{
|
||||
"cmake" :
|
||||
{
|
||||
"generator" :
|
||||
{
|
||||
"multiConfig" : false,
|
||||
"name" : "MinGW Makefiles"
|
||||
},
|
||||
"paths" :
|
||||
{
|
||||
"cmake" : "D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe",
|
||||
"cpack" : "D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cpack.exe",
|
||||
"ctest" : "D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/ctest.exe",
|
||||
"root" : "D:/clion/CLion 2023.2.2/bin/cmake/win/x64/share/cmake-3.26"
|
||||
},
|
||||
"version" :
|
||||
{
|
||||
"isDirty" : false,
|
||||
"major" : 3,
|
||||
"minor" : 26,
|
||||
"patch" : 4,
|
||||
"string" : "3.26.4",
|
||||
"suffix" : ""
|
||||
}
|
||||
},
|
||||
"objects" :
|
||||
[
|
||||
{
|
||||
"jsonFile" : "codemodel-v2-f154511db966dea83028.json",
|
||||
"kind" : "codemodel",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 5
|
||||
}
|
||||
},
|
||||
{
|
||||
"jsonFile" : "cache-v2-66e677dd5570c7783f8d.json",
|
||||
"kind" : "cache",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 0
|
||||
}
|
||||
},
|
||||
{
|
||||
"jsonFile" : "cmakeFiles-v1-98b572fb52e402116530.json",
|
||||
"kind" : "cmakeFiles",
|
||||
"version" :
|
||||
{
|
||||
"major" : 1,
|
||||
"minor" : 0
|
||||
}
|
||||
},
|
||||
{
|
||||
"jsonFile" : "toolchains-v1-4ab90673517ad6ca701e.json",
|
||||
"kind" : "toolchains",
|
||||
"version" :
|
||||
{
|
||||
"major" : 1,
|
||||
"minor" : 0
|
||||
}
|
||||
}
|
||||
],
|
||||
"reply" :
|
||||
{
|
||||
"cache-v2" :
|
||||
{
|
||||
"jsonFile" : "cache-v2-66e677dd5570c7783f8d.json",
|
||||
"kind" : "cache",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 0
|
||||
}
|
||||
},
|
||||
"cmakeFiles-v1" :
|
||||
{
|
||||
"jsonFile" : "cmakeFiles-v1-98b572fb52e402116530.json",
|
||||
"kind" : "cmakeFiles",
|
||||
"version" :
|
||||
{
|
||||
"major" : 1,
|
||||
"minor" : 0
|
||||
}
|
||||
},
|
||||
"codemodel-v2" :
|
||||
{
|
||||
"jsonFile" : "codemodel-v2-f154511db966dea83028.json",
|
||||
"kind" : "codemodel",
|
||||
"version" :
|
||||
{
|
||||
"major" : 2,
|
||||
"minor" : 5
|
||||
}
|
||||
},
|
||||
"toolchains-v1" :
|
||||
{
|
||||
"jsonFile" : "toolchains-v1-4ab90673517ad6ca701e.json",
|
||||
"kind" : "toolchains",
|
||||
"version" :
|
||||
{
|
||||
"major" : 1,
|
||||
"minor" : 0
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
File diff suppressed because it is too large
Load Diff
|
@ -42,7 +42,7 @@ CMAKE_ASM_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG
|
|||
|
||||
//Choose the type of build, options are: None Debug Release RelWithDebInfo
|
||||
// MinSizeRel ...
|
||||
CMAKE_BUILD_TYPE:STRING=Debug
|
||||
CMAKE_BUILD_TYPE:STRING=
|
||||
|
||||
//Id string of the compiler for the CodeBlocks IDE. Automatically
|
||||
// detected when left empty
|
||||
|
@ -137,8 +137,8 @@ CMAKE_INSTALL_PREFIX:PATH=C:/Program Files (x86)/uav
|
|||
//Path to a program.
|
||||
CMAKE_LINKER:FILEPATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/arm-none-eabi-ld.exe
|
||||
|
||||
//No help, variable specified on the command line.
|
||||
CMAKE_MAKE_PROGRAM:UNINITIALIZED=D:/MinGW/mingw64/bin/mingw32-make.exe
|
||||
//Path to a program.
|
||||
CMAKE_MAKE_PROGRAM:FILEPATH=D:/MinGW/mingw64/bin/mingw32-make.exe
|
||||
|
||||
//Flags used by the linker during the creation of modules during
|
||||
// all build types.
|
||||
|
@ -378,6 +378,8 @@ CMAKE_GENERATOR_TOOLSET:INTERNAL=
|
|||
CMAKE_HOME_DIRECTORY:INTERNAL=D:/zhandui/cqdm/uav
|
||||
//ADVANCED property for variable: CMAKE_LINKER
|
||||
CMAKE_LINKER-ADVANCED:INTERNAL=1
|
||||
//ADVANCED property for variable: CMAKE_MAKE_PROGRAM
|
||||
CMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1
|
||||
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS
|
||||
CMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1
|
||||
//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -135,8 +135,8 @@ events:
|
|||
checks:
|
||||
- "Detecting C compiler ABI info"
|
||||
directories:
|
||||
source: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4"
|
||||
binary: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4"
|
||||
source: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp"
|
||||
binary: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp"
|
||||
cmakeVariables:
|
||||
CMAKE_C_FLAGS: ""
|
||||
CMAKE_C_FLAGS_DEBUG: "-g"
|
||||
|
@ -145,12 +145,12 @@ events:
|
|||
variable: "CMAKE_C_ABI_COMPILED"
|
||||
cached: true
|
||||
stdout: |
|
||||
Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4
|
||||
Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp
|
||||
|
||||
Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_4e014/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_4e014.dir\\build.make CMakeFiles/cmTC_4e014.dir/build
|
||||
mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4'
|
||||
Building C object CMakeFiles/cmTC_4e014.dir/CMakeCCompilerABI.c.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c"
|
||||
Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_e836c/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_e836c.dir\\build.make CMakeFiles/cmTC_e836c.dir/build
|
||||
mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp'
|
||||
Building C object CMakeFiles/cmTC_e836c.dir/CMakeCCompilerABI.c.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c"
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe
|
||||
Target: arm-none-eabi
|
||||
|
@ -158,8 +158,8 @@ events:
|
|||
Thread model: single
|
||||
Supported LTO compression algorithms: zlib
|
||||
gcc version 12.3.1 20230626 (GNU Tools for STM32 12.3.rel1.20240612-1315)
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles\\cmTC_4e014.dir\\ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccqyel3c.s
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles\\cmTC_e836c.dir\\ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccEK6alR.s
|
||||
GNU C17 (GNU Tools for STM32 12.3.rel1.20240612-1315) version 12.3.1 20230626 (arm-none-eabi)
|
||||
compiled by GNU C version 7.3-win32 20180312, GMP version 6.2.1, MPFR version 3.1.6, MPC version 1.0.3, isl version isl-0.15-1-g835ea3a-GMP
|
||||
|
||||
|
@ -180,18 +180,18 @@ events:
|
|||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
Compiler executable checksum: 8c85bce3e8a10a7ec33a6a6bd0176b53
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccqyel3c.s
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccEK6alR.s
|
||||
GNU assembler version 2.40.0 (arm-none-eabi) using BFD version (GNU Tools for STM32 12.3.rel1.20240612-1315) 2.40.0.20230627
|
||||
COMPILER_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/
|
||||
LIBRARY_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/lib/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../arm-none-eabi/lib/
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.'
|
||||
Linking C static library libcmTC_4e014.a
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_4e014.dir\\cmake_clean_target.cmake
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_4e014.dir\\link.txt --verbose=1
|
||||
arm-none-eabi-ar qc libcmTC_4e014.a CMakeFiles/cmTC_4e014.dir/CMakeCCompilerABI.c.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_4e014.a
|
||||
mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4'
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.'
|
||||
Linking C static library libcmTC_e836c.a
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_e836c.dir\\cmake_clean_target.cmake
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_e836c.dir\\link.txt --verbose=1
|
||||
arm-none-eabi-ar qc libcmTC_e836c.a CMakeFiles/cmTC_e836c.dir/CMakeCCompilerABI.c.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_e836c.a
|
||||
mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp'
|
||||
|
||||
exitCode: 0
|
||||
-
|
||||
|
@ -229,12 +229,12 @@ events:
|
|||
message: |
|
||||
Parsed C implicit link information:
|
||||
link line regex: [^( *|.*[/\\])(arm-none-eabi-ld\\.exe|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\\]+-)?ld|collect2)[^/\\]*( |$)]
|
||||
ignore line: [Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4]
|
||||
ignore line: [Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp]
|
||||
ignore line: []
|
||||
ignore line: [Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_4e014/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_4e014.dir\\build.make CMakeFiles/cmTC_4e014.dir/build]
|
||||
ignore line: [mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4']
|
||||
ignore line: [Building C object CMakeFiles/cmTC_4e014.dir/CMakeCCompilerABI.c.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c"]
|
||||
ignore line: [Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_e836c/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_e836c.dir\\build.make CMakeFiles/cmTC_e836c.dir/build]
|
||||
ignore line: [mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp']
|
||||
ignore line: [Building C object CMakeFiles/cmTC_e836c.dir/CMakeCCompilerABI.c.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c"]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-gcc.exe]
|
||||
ignore line: [Target: arm-none-eabi]
|
||||
|
@ -242,8 +242,8 @@ events:
|
|||
ignore line: [Thread model: single]
|
||||
ignore line: [Supported LTO compression algorithms: zlib]
|
||||
ignore line: [gcc version 12.3.1 20230626 (GNU Tools for STM32 12.3.rel1.20240612-1315) ]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles\\cmTC_4e014.dir\\ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccqyel3c.s]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCCompilerABI.c -quiet -dumpdir CMakeFiles\\cmTC_e836c.dir\\ -dumpbase CMakeCCompilerABI.c.c -dumpbase-ext .c -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccEK6alR.s]
|
||||
ignore line: [GNU C17 (GNU Tools for STM32 12.3.rel1.20240612-1315) version 12.3.1 20230626 (arm-none-eabi)]
|
||||
ignore line: [ compiled by GNU C version 7.3-win32 20180312 GMP version 6.2.1 MPFR version 3.1.6 MPC version 1.0.3 isl version isl-0.15-1-g835ea3a-GMP]
|
||||
ignore line: []
|
||||
|
@ -264,8 +264,8 @@ events:
|
|||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [Compiler executable checksum: 8c85bce3e8a10a7ec33a6a6bd0176b53]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccqyel3c.s]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccEK6alR.s]
|
||||
ignore line: [GNU assembler version 2.40.0 (arm-none-eabi) using BFD version (GNU Tools for STM32 12.3.rel1.20240612-1315) 2.40.0.20230627]
|
||||
ignore line: [COMPILER_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/]
|
||||
|
@ -274,13 +274,13 @@ events:
|
|||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/lib/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../arm-none-eabi/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_4e014.dir\\CMakeCCompilerABI.c.']
|
||||
ignore line: [Linking C static library libcmTC_4e014.a]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_4e014.dir\\cmake_clean_target.cmake]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_4e014.dir\\link.txt --verbose=1]
|
||||
ignore line: [arm-none-eabi-ar qc libcmTC_4e014.a CMakeFiles/cmTC_4e014.dir/CMakeCCompilerABI.c.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_4e014.a]
|
||||
ignore line: [mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-r99yb4']
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_e836c.dir\\CMakeCCompilerABI.c.']
|
||||
ignore line: [Linking C static library libcmTC_e836c.a]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_e836c.dir\\cmake_clean_target.cmake]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_e836c.dir\\link.txt --verbose=1]
|
||||
ignore line: [arm-none-eabi-ar qc libcmTC_e836c.a CMakeFiles/cmTC_e836c.dir/CMakeCCompilerABI.c.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_e836c.a]
|
||||
ignore line: [mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-otjvrp']
|
||||
ignore line: []
|
||||
ignore line: []
|
||||
implicit libs: []
|
||||
|
@ -298,8 +298,8 @@ events:
|
|||
checks:
|
||||
- "Detecting CXX compiler ABI info"
|
||||
directories:
|
||||
source: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h"
|
||||
binary: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h"
|
||||
source: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab"
|
||||
binary: "D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab"
|
||||
cmakeVariables:
|
||||
CMAKE_CXX_FLAGS: ""
|
||||
CMAKE_CXX_FLAGS_DEBUG: "-g"
|
||||
|
@ -308,12 +308,12 @@ events:
|
|||
variable: "CMAKE_CXX_ABI_COMPILED"
|
||||
cached: true
|
||||
stdout: |
|
||||
Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h
|
||||
Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab
|
||||
|
||||
Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_3c92a/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_3c92a.dir\\build.make CMakeFiles/cmTC_3c92a.dir/build
|
||||
mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h'
|
||||
Building CXX object CMakeFiles/cmTC_3c92a.dir/CMakeCXXCompilerABI.cpp.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp"
|
||||
Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_afb61/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_afb61.dir\\build.make CMakeFiles/cmTC_afb61.dir/build
|
||||
mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab'
|
||||
Building CXX object CMakeFiles/cmTC_afb61.dir/CMakeCXXCompilerABI.cpp.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp"
|
||||
Using built-in specs.
|
||||
COLLECT_GCC=D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe
|
||||
Target: arm-none-eabi
|
||||
|
@ -321,8 +321,8 @@ events:
|
|||
Thread model: single
|
||||
Supported LTO compression algorithms: zlib
|
||||
gcc version 12.3.1 20230626 (GNU Tools for STM32 12.3.rel1.20240612-1315)
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1plus.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles\\cmTC_3c92a.dir\\ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccLUnYVs.s
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1plus.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles\\cmTC_afb61.dir\\ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccRMi2rb.s
|
||||
GNU C++17 (GNU Tools for STM32 12.3.rel1.20240612-1315) version 12.3.1 20230626 (arm-none-eabi)
|
||||
compiled by GNU C version 7.3-win32 20180312, GMP version 6.2.1, MPFR version 3.1.6, MPC version 1.0.3, isl version isl-0.15-1-g835ea3a-GMP
|
||||
|
||||
|
@ -349,18 +349,18 @@ events:
|
|||
|
||||
GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072
|
||||
Compiler executable checksum: e40f213a8b38594a68f1558fe98e1d38
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccLUnYVs.s
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\'
|
||||
D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccRMi2rb.s
|
||||
GNU assembler version 2.40.0 (arm-none-eabi) using BFD version (GNU Tools for STM32 12.3.rel1.20240612-1315) 2.40.0.20230627
|
||||
COMPILER_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/
|
||||
LIBRARY_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/lib/;D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../arm-none-eabi/lib/
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.'
|
||||
Linking CXX static library libcmTC_3c92a.a
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_3c92a.dir\\cmake_clean_target.cmake
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_3c92a.dir\\link.txt --verbose=1
|
||||
arm-none-eabi-ar qc libcmTC_3c92a.a CMakeFiles/cmTC_3c92a.dir/CMakeCXXCompilerABI.cpp.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_3c92a.a
|
||||
mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h'
|
||||
COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.'
|
||||
Linking CXX static library libcmTC_afb61.a
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_afb61.dir\\cmake_clean_target.cmake
|
||||
"D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_afb61.dir\\link.txt --verbose=1
|
||||
arm-none-eabi-ar qc libcmTC_afb61.a CMakeFiles/cmTC_afb61.dir/CMakeCXXCompilerABI.cpp.obj
|
||||
D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_afb61.a
|
||||
mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab'
|
||||
|
||||
exitCode: 0
|
||||
-
|
||||
|
@ -410,12 +410,12 @@ events:
|
|||
message: |
|
||||
Parsed CXX implicit link information:
|
||||
link line regex: [^( *|.*[/\\])(arm-none-eabi-ld\\.exe|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\\]+-)?ld|collect2)[^/\\]*( |$)]
|
||||
ignore line: [Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h]
|
||||
ignore line: [Change Dir: D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab]
|
||||
ignore line: []
|
||||
ignore line: [Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_3c92a/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_3c92a.dir\\build.make CMakeFiles/cmTC_3c92a.dir/build]
|
||||
ignore line: [mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h']
|
||||
ignore line: [Building CXX object CMakeFiles/cmTC_3c92a.dir/CMakeCXXCompilerABI.cpp.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp"]
|
||||
ignore line: [Run Build Command(s):D:/clion/CLion 2023.2.2/bin/cmake/win/x64/bin/cmake.exe -E env VERBOSE=1 D:/MinGW/mingw64/bin/mingw32-make.exe -f Makefile cmTC_afb61/fast && D:/MinGW/mingw64/bin/mingw32-make.exe -f CMakeFiles\\cmTC_afb61.dir\\build.make CMakeFiles/cmTC_afb61.dir/build]
|
||||
ignore line: [mingw32-make.exe[1]: Entering directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab']
|
||||
ignore line: [Building CXX object CMakeFiles/cmTC_afb61.dir/CMakeCXXCompilerABI.cpp.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe -fdiagnostics-color=always -v -o CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj -c "D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp"]
|
||||
ignore line: [Using built-in specs.]
|
||||
ignore line: [COLLECT_GCC=D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-g++.exe]
|
||||
ignore line: [Target: arm-none-eabi]
|
||||
|
@ -423,8 +423,8 @@ events:
|
|||
ignore line: [Thread model: single]
|
||||
ignore line: [Supported LTO compression algorithms: zlib]
|
||||
ignore line: [gcc version 12.3.1 20230626 (GNU Tools for STM32 12.3.rel1.20240612-1315) ]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1plus.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles\\cmTC_3c92a.dir\\ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccLUnYVs.s]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/cc1plus.exe -quiet -v -iprefix D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../lib/gcc/arm-none-eabi/12.3.1/ -isysroot D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\../arm-none-eabi -D__USES_INITFINI__ D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\share\\cmake-3.26\\Modules\\CMakeCXXCompilerABI.cpp -quiet -dumpdir CMakeFiles\\cmTC_afb61.dir\\ -dumpbase CMakeCXXCompilerABI.cpp.cpp -dumpbase-ext .cpp -mcpu=arm7tdmi -mfloat-abi=soft -marm -mlibarch=armv4t -march=armv4t -version -fdiagnostics-color=always -o C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccRMi2rb.s]
|
||||
ignore line: [GNU C++17 (GNU Tools for STM32 12.3.rel1.20240612-1315) version 12.3.1 20230626 (arm-none-eabi)]
|
||||
ignore line: [ compiled by GNU C version 7.3-win32 20180312 GMP version 6.2.1 MPFR version 3.1.6 MPC version 1.0.3 isl version isl-0.15-1-g835ea3a-GMP]
|
||||
ignore line: []
|
||||
|
@ -451,8 +451,8 @@ events:
|
|||
ignore line: []
|
||||
ignore line: [GGC heuristics: --param ggc-min-expand=100 --param ggc-min-heapsize=131072]
|
||||
ignore line: [Compiler executable checksum: e40f213a8b38594a68f1558fe98e1d38]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccLUnYVs.s]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\']
|
||||
ignore line: [ D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/bin/as.exe -v -march=armv4t -mfloat-abi=soft -meabi=5 -o CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj C:\\Users\\zyx12\\AppData\\Local\\Temp\\ccRMi2rb.s]
|
||||
ignore line: [GNU assembler version 2.40.0 (arm-none-eabi) using BFD version (GNU Tools for STM32 12.3.rel1.20240612-1315) 2.40.0.20230627]
|
||||
ignore line: [COMPILER_PATH=D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/]
|
||||
|
@ -461,13 +461,13 @@ events:
|
|||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/lib/]
|
||||
ignore line: [D:/STM32CubeCLT_1.16.0/GNU-tools-for-STM32/bin/../arm-none-eabi/lib/]
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_3c92a.dir\\CMakeCXXCompilerABI.cpp.']
|
||||
ignore line: [Linking CXX static library libcmTC_3c92a.a]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_3c92a.dir\\cmake_clean_target.cmake]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_3c92a.dir\\link.txt --verbose=1]
|
||||
ignore line: [arm-none-eabi-ar qc libcmTC_3c92a.a CMakeFiles/cmTC_3c92a.dir/CMakeCXXCompilerABI.cpp.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_3c92a.a]
|
||||
ignore line: [mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-alhh3h']
|
||||
ignore line: [COLLECT_GCC_OPTIONS='-fdiagnostics-color=always' '-v' '-o' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.obj' '-c' '-mcpu=arm7tdmi' '-mfloat-abi=soft' '-marm' '-mlibarch=armv4t' '-march=armv4t' '-dumpdir' 'CMakeFiles\\cmTC_afb61.dir\\CMakeCXXCompilerABI.cpp.']
|
||||
ignore line: [Linking CXX static library libcmTC_afb61.a]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -P CMakeFiles\\cmTC_afb61.dir\\cmake_clean_target.cmake]
|
||||
ignore line: ["D:\\clion\\CLion 2023.2.2\\bin\\cmake\\win\\x64\\bin\\cmake.exe" -E cmake_link_script CMakeFiles\\cmTC_afb61.dir\\link.txt --verbose=1]
|
||||
ignore line: [arm-none-eabi-ar qc libcmTC_afb61.a CMakeFiles/cmTC_afb61.dir/CMakeCXXCompilerABI.cpp.obj]
|
||||
ignore line: [D:\\STM32CubeCLT_1.16.0\\GNU-tools-for-STM32\\bin\\arm-none-eabi-ranlib.exe libcmTC_afb61.a]
|
||||
ignore line: [mingw32-make.exe[1]: Leaving directory 'D:/zhandui/cqdm/uav/cmake-build-debug/CMakeFiles/CMakeScratch/TryCompile-dlekab']
|
||||
ignore line: []
|
||||
ignore line: []
|
||||
implicit libs: []
|
||||
|
|
|
@ -31,6 +31,7 @@ set(CMAKE_MAKEFILE_DEPENDS
|
|||
"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/CMakeMinGWFindMake.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"
|
||||
|
|
|
@ -1,4 +1,12 @@
|
|||
"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\uav -B D:\zhandui\cqdm\uav\cmake-build-debug
|
||||
-- Minimal optimization, debug info included
|
||||
-- Configuring done (0.1s)
|
||||
You have changed variables that require your cache to be deleted.
|
||||
Configure will be re-run and you may have to reset some variables.
|
||||
The following variables have changed:
|
||||
CMAKE_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
|
||||
CMAKE_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
|
||||
|
||||
-- The C compiler identification is GNU 12.3.1
|
||||
-- The CXX compiler identification is GNU 12.3.1
|
||||
-- The ASM compiler identification is GNU
|
||||
|
@ -14,6 +22,6 @@
|
|||
-- Detecting CXX compile features
|
||||
-- Detecting CXX compile features - done
|
||||
-- Minimal optimization, debug info included
|
||||
-- Configuring done (1.9s)
|
||||
-- Configuring done (1.6s)
|
||||
-- Generating done (0.1s)
|
||||
-- Build files have been written to: D:/zhandui/cqdm/uav/cmake-build-debug
|
||||
|
|
Binary file not shown.
|
@ -74,12 +74,12 @@ set(CMAKE_ASM_TARGET_INCLUDE_PATH
|
|||
"D:/zhandui/cqdm/uav/modules/motor/DJImotor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/HTmotor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/LKmotor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/pwmmotor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/servo_motor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/step_motor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/ECmotor"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/DMmotor"
|
||||
"D:/zhandui/cqdm/uav/application"
|
||||
"D:/zhandui/cqdm/uav/application/chassis"
|
||||
"D:/zhandui/cqdm/uav/application/cmd"
|
||||
"D:/zhandui/cqdm/uav/application/gimbal"
|
||||
"D:/zhandui/cqdm/uav/application/shoot"
|
||||
|
@ -161,7 +161,6 @@ set(CMAKE_DEPENDS_DEPENDENCY_FILES
|
|||
"D:/zhandui/cqdm/uav/Src/usbd_cdc_if.c" "CMakeFiles/uav.elf.dir/Src/usbd_cdc_if.c.obj" "gcc" "CMakeFiles/uav.elf.dir/Src/usbd_cdc_if.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/Src/usbd_conf.c" "CMakeFiles/uav.elf.dir/Src/usbd_conf.c.obj" "gcc" "CMakeFiles/uav.elf.dir/Src/usbd_conf.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/Src/usbd_desc.c" "CMakeFiles/uav.elf.dir/Src/usbd_desc.c.obj" "gcc" "CMakeFiles/uav.elf.dir/Src/usbd_desc.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/application/chassis/chassis.c" "CMakeFiles/uav.elf.dir/application/chassis/chassis.c.obj" "gcc" "CMakeFiles/uav.elf.dir/application/chassis/chassis.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/application/cmd/robot_cmd.c" "CMakeFiles/uav.elf.dir/application/cmd/robot_cmd.c.obj" "gcc" "CMakeFiles/uav.elf.dir/application/cmd/robot_cmd.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/application/gimbal/gimbal.c" "CMakeFiles/uav.elf.dir/application/gimbal/gimbal.c.obj" "gcc" "CMakeFiles/uav.elf.dir/application/gimbal/gimbal.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/application/robot.c" "CMakeFiles/uav.elf.dir/application/robot.c.obj" "gcc" "CMakeFiles/uav.elf.dir/application/robot.c.obj.d"
|
||||
|
@ -179,6 +178,7 @@ set(CMAKE_DEPENDS_DEPENDENCY_FILES
|
|||
"D:/zhandui/cqdm/uav/bsp/usart/bsp_usart.c" "CMakeFiles/uav.elf.dir/bsp/usart/bsp_usart.c.obj" "gcc" "CMakeFiles/uav.elf.dir/bsp/usart/bsp_usart.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/bsp/usb/bsp_usb.c" "CMakeFiles/uav.elf.dir/bsp/usb/bsp_usb.c.obj" "gcc" "CMakeFiles/uav.elf.dir/bsp/usb/bsp_usb.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/BMI088/bmi088.c" "CMakeFiles/uav.elf.dir/modules/BMI088/bmi088.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/BMI088/bmi088.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/RGB/RGB.c" "CMakeFiles/uav.elf.dir/modules/RGB/RGB.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/RGB/RGB.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/TFminiPlus/tfminiplus.c" "CMakeFiles/uav.elf.dir/modules/TFminiPlus/tfminiplus.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/TFminiPlus/tfminiplus.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/alarm/buzzer.c" "CMakeFiles/uav.elf.dir/modules/alarm/buzzer.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/alarm/buzzer.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/algorithm/QuaternionEKF.c" "CMakeFiles/uav.elf.dir/modules/algorithm/QuaternionEKF.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/algorithm/QuaternionEKF.c.obj.d"
|
||||
|
@ -204,6 +204,7 @@ set(CMAKE_DEPENDS_DEPENDENCY_FILES
|
|||
"D:/zhandui/cqdm/uav/modules/motor/HTmotor/HT04.c" "CMakeFiles/uav.elf.dir/modules/motor/HTmotor/HT04.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/HTmotor/HT04.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/LKmotor/LK9025.c" "CMakeFiles/uav.elf.dir/modules/motor/LKmotor/LK9025.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/LKmotor/LK9025.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/motor_task.c" "CMakeFiles/uav.elf.dir/modules/motor/motor_task.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/motor_task.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/pwmmotor/snail.c" "CMakeFiles/uav.elf.dir/modules/motor/pwmmotor/snail.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/pwmmotor/snail.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/servo_motor/servo_motor.c" "CMakeFiles/uav.elf.dir/modules/motor/servo_motor/servo_motor.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/servo_motor/servo_motor.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/motor/step_motor/step_motor.c" "CMakeFiles/uav.elf.dir/modules/motor/step_motor/step_motor.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/motor/step_motor/step_motor.c.obj.d"
|
||||
"D:/zhandui/cqdm/uav/modules/oled/oled.c" "CMakeFiles/uav.elf.dir/modules/oled/oled.c.obj" "gcc" "CMakeFiles/uav.elf.dir/modules/oled/oled.c.obj.d"
|
||||
|
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -1,127 +0,0 @@
|
|||
CMakeFiles/uav.elf.dir/application/chassis/chassis.c.obj: \
|
||||
D:\zhandui\cqdm\uav\application\chassis\chassis.c \
|
||||
D:\zhandui\cqdm\uav\application\chassis\chassis.h \
|
||||
D:\zhandui\cqdm\uav\application/robot_def.h \
|
||||
D:\zhandui\cqdm\uav\modules\imu/ins_task.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/include/stdint.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/stdint.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/machine/_default_types.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/features.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/_newlib_version.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/_intsup.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/_stdint.h \
|
||||
D:\zhandui\cqdm\uav\modules\imu/BMI088driver.h \
|
||||
D:\zhandui\cqdm\uav\Inc/main.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal.h \
|
||||
D:\zhandui\cqdm\uav\Inc/stm32f4xx_hal_conf.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_rcc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_def.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Device\ST\STM32F4xx\Include/stm32f4xx.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Device\ST\STM32F4xx\Include/stm32f407xx.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Include/core_cm4.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Include/cmsis_version.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Include/cmsis_compiler.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Include/cmsis_gcc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Include/mpu_armv7.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Device\ST\STM32F4xx\Include/system_stm32f4xx.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/Legacy/stm32_hal_legacy.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/include/stddef.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_rcc_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_gpio.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_gpio_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_exti.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_dma.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_dma_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_cortex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_adc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_ll_adc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_adc_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_can.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_crc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_dac.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_dac_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_flash.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_flash_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_flash_ramfunc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_i2c.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_i2c_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_pwr.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_pwr_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_rng.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_rtc.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_rtc_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_spi.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_tim.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_tim_ex.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_uart.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_pcd.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_ll_usb.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\STM32F4xx_HAL_Driver\Inc/stm32f4xx_hal_pcd_ex.h \
|
||||
D:\zhandui\cqdm\uav\application/robot.h \
|
||||
D:\zhandui\cqdm\uav\bsp\log/bsp_log.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\SEGGER\RTT/SEGGER_RTT.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\SEGGER\RTT/../Config/SEGGER_RTT_Conf.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/stdlib.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/machine/ieeefp.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/_ansi.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/newlib.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/config.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/reent.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/_ansi.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/_types.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/machine/_types.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/lock.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/cdefs.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/machine/stdlib.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/alloca.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/include/stdarg.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\SEGGER\Config/SEGGER_RTT_Conf.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/stdio.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/stdio.h \
|
||||
D:\zhandui\cqdm\uav\modules\algorithm/QuaternionEKF.h \
|
||||
D:\zhandui\cqdm\uav\modules\algorithm/kalman_filter.h \
|
||||
D:\zhandui\cqdm\uav\Drivers\CMSIS\Device\ST\STM32F4xx\Include/stm32f407xx.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\ST\ARM\DSP\Inc/arm_math.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/string.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/_locale.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/strings.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/sys/string.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/math.h \
|
||||
D:\zhandui\cqdm\uav\modules\master_machine/master_process.h \
|
||||
D:\zhandui\cqdm\uav\bsp\usart/bsp_usart.h \
|
||||
D:\zhandui\cqdm\uav\modules\master_machine/seasky_protocol.h \
|
||||
D:\zhandui\cqdm\uav\modules\motor\DJImotor/dji_motor.h \
|
||||
D:\zhandui\cqdm\uav\bsp\can/bsp_can.h D:\zhandui\cqdm\uav\Inc/can.h \
|
||||
D:\zhandui\cqdm\uav\Inc/main.h \
|
||||
D:\zhandui\cqdm\uav\modules\algorithm/controller.h \
|
||||
D:\STM32CubeCLT_1.16.0\GNU-tools-for-STM32\bin\../lib/gcc/arm-none-eabi/12.3.1/../../../../arm-none-eabi/include/memory.h \
|
||||
D:\zhandui\cqdm\uav\bsp\dwt/bsp_dwt.h \
|
||||
D:\zhandui\cqdm\uav\modules\motor/motor_def.h \
|
||||
D:\zhandui\cqdm\uav\modules\daemon/daemon.h \
|
||||
D:\zhandui\cqdm\uav\modules\super_cap/super_cap.h \
|
||||
D:\zhandui\cqdm\uav\modules\message_center/message_center.h \
|
||||
D:\zhandui\cqdm\uav\modules\referee/referee_task.h \
|
||||
D:\zhandui\cqdm\uav\modules\referee/rm_referee.h \
|
||||
D:\zhandui\cqdm\uav\Inc/usart.h \
|
||||
D:\zhandui\cqdm\uav\modules\referee/referee_protocol.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/FreeRTOS.h \
|
||||
D:\zhandui\cqdm\uav\Inc/FreeRTOSConfig.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/projdefs.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/portable.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/deprecated_definitions.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\portable\GCC\ARM_CM4F/portmacro.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/mpu_wrappers.h \
|
||||
D:\zhandui\cqdm\uav\modules/general_def.h \
|
||||
D:\zhandui\cqdm\uav\modules\referee/referee_UI.h \
|
||||
D:\zhandui\cqdm\uav\modules\algorithm/user_lib.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\CMSIS_RTOS/cmsis_os.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/task.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/list.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/timers.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/task.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/queue.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/semphr.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/queue.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/event_groups.h \
|
||||
D:\zhandui\cqdm\uav\Middlewares\Third_Party\FreeRTOS\Source\include/timers.h \
|
||||
D:\zhandui\cqdm\uav\modules\vofa/vofa.h
|
Binary file not shown.
Binary file not shown.
|
@ -98,6 +98,7 @@ CMakeFiles/uav.elf.dir/application/gimbal/gimbal.c.obj: \
|
|||
D:\zhandui\cqdm\uav\bsp\dwt/bsp_dwt.h \
|
||||
D:\zhandui\cqdm\uav\modules\motor/motor_def.h \
|
||||
D:\zhandui\cqdm\uav\modules\daemon/daemon.h \
|
||||
D:\zhandui\cqdm\uav\modules\motor\DMmotor/dmmotor.h \
|
||||
D:\zhandui\cqdm\uav\modules\message_center/message_center.h \
|
||||
D:\zhandui\cqdm\uav\modules/general_def.h \
|
||||
D:\zhandui\cqdm\uav\modules\BMI088/bmi088.h \
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue