保存
This commit is contained in:
parent
7c883d09d8
commit
5c8c1fc474
@ -1,22 +1,17 @@
|
|||||||
#include "module/aimbot.h"
|
#include "module/aimbot.h"
|
||||||
#include "device/device.h"
|
#include "device/device.h"
|
||||||
#include "bsp/uart.h"
|
#include "bsp/uart.h"
|
||||||
#include "bsp/fdcan.h"
|
|
||||||
#include "component/crc16.h"
|
#include "component/crc16.h"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
/* =====================================================================
|
/* =====================================================================
|
||||||
* CAN 帧索引(反馈方向:下层板 → 上层板)
|
* FDCAN 帧索引(反馈方向:下层板?上层板)
|
||||||
|
* 注:上层板使用自己的IMU,下层板只发送射击数据与模式
|
||||||
* ===================================================================== */
|
* ===================================================================== */
|
||||||
#define FB_FRAME_Q01 0u /* IMU 四元数 q[0](w), q[1](x) */
|
#define FB_FRAME_DATA 0u /* 弹速(4B)+弹数(2B)+模式(1B)+保留(1B) */
|
||||||
#define FB_FRAME_Q23 1u /* IMU 四元数 q[2](y), q[3](z) */
|
|
||||||
#define FB_FRAME_EULR 2u /* IMU 欧拉角 yaw, pitch (float x2) */
|
|
||||||
#define FB_FRAME_VEL 3u /* IMU 角速度 yaw_vel, pitch_vel (float x2) */
|
|
||||||
#define FB_FRAME_SHOOT 4u /* 弹速(4B)+弹数(2B)+模式(1B)+保留(1B) */
|
|
||||||
#define FB_FRAME_MOTOR 5u /* 云台电机绝对角度 yaw, pit (float x2) */
|
|
||||||
|
|
||||||
/* =====================================================================
|
/* =====================================================================
|
||||||
* UART 通信接口(上层板 ↔ 上位机 PC)
|
* UART 通信接口(上层板 <EFBFBD>?上位<EFBFBD>?PC<EFBFBD>?
|
||||||
* ===================================================================== */
|
* ===================================================================== */
|
||||||
|
|
||||||
int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai) {
|
int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai) {
|
||||||
@ -27,47 +22,45 @@ int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
int8_t Aimbot_AIGetResult(Aimbot_AI_t *ai, Aimbot_AIResult_t *result) {
|
int8_t Aimbot_AIGetResult(Aimbot_AI_t *ai, Aimbot_AIResult_t *result) {
|
||||||
if (ai->id != ID_AI) {
|
if (ai->head[0] != 'M' || ai->head[1] != 'R') {
|
||||||
return DEVICE_ERR;
|
return DEVICE_ERR;
|
||||||
}
|
}
|
||||||
if (!CRC16_Verify((const uint8_t *)ai, sizeof(*ai))) {
|
if (!CRC16_Verify((const uint8_t *)ai, sizeof(*ai))) {
|
||||||
return DEVICE_ERR;
|
return DEVICE_ERR;
|
||||||
}
|
}
|
||||||
result->mode = ai->data.mode;
|
result->mode = ai->mode;
|
||||||
result->gimbal_t.setpoint.yaw = ai->data.yaw;
|
result->gimbal_t.setpoint.yaw = ai->yaw;
|
||||||
result->gimbal_t.vel.yaw = ai->data.yaw_vel;
|
result->gimbal_t.vel.yaw = ai->yaw_vel;
|
||||||
result->gimbal_t.accl.yaw = ai->data.yaw_acc;
|
result->gimbal_t.accl.yaw = ai->yaw_acc;
|
||||||
result->gimbal_t.setpoint.pit = ai->data.pitch;
|
result->gimbal_t.setpoint.pit = ai->pitch;
|
||||||
result->gimbal_t.vel.pit = ai->data.pitch_vel;
|
result->gimbal_t.vel.pit = ai->pitch_vel;
|
||||||
result->gimbal_t.accl.pit = ai->data.pitch_acc;
|
result->gimbal_t.accl.pit = ai->pitch_acc;
|
||||||
result->chassis_t.Vx = ai->data.vx;
|
|
||||||
result->chassis_t.Vy = ai->data.vy;
|
|
||||||
result->chassis_t.Vw = ai->data.wz;
|
|
||||||
return DEVICE_OK;
|
return DEVICE_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 打包 MCU 数据(UART 发给上位机格式),修正了原始实现中的字段错误。
|
* @brief 打包 MCU 数据(UART 发给上位机格式),修正了原始实现中的字段错误<EFBFBD>?
|
||||||
* 四元数来自 quat 参数;欧拉角、角速度来自 gimbal_fb->imu。
|
* 四元数来<EFBFBD>?quat 参数;欧拉角、角速度来自 gimbal_fb->imu<EFBFBD>?
|
||||||
*/
|
*/
|
||||||
int8_t Aimbot_MCUPack(Aimbot_MCU_t *mcu, const Gimbal_Feedback_t *gimbal_fb,
|
int8_t Aimbot_MCUPack(Aimbot_MCU_t *mcu, const Gimbal_Feedback_t *gimbal_fb,
|
||||||
const AHRS_Quaternion_t *quat,
|
const AHRS_Quaternion_t *quat,
|
||||||
float bullet_speed, uint16_t bullet_count) {
|
float bullet_speed, uint16_t bullet_count, uint8_t mode) {
|
||||||
if (mcu == NULL || gimbal_fb == NULL || quat == NULL) {
|
if (mcu == NULL || gimbal_fb == NULL || quat == NULL) {
|
||||||
return DEVICE_ERR_NULL;
|
return DEVICE_ERR_NULL;
|
||||||
}
|
}
|
||||||
mcu->id = ID_MCU;
|
mcu->head[0] = 'M';
|
||||||
mcu->data.mode = 0;
|
mcu->head[1] = 'R';
|
||||||
mcu->data.q[0] = quat->q0;
|
mcu->mode = mode;
|
||||||
mcu->data.q[1] = quat->q1;
|
mcu->q[0] = quat->q0;
|
||||||
mcu->data.q[2] = quat->q2;
|
mcu->q[1] = quat->q1;
|
||||||
mcu->data.q[3] = quat->q3;
|
mcu->q[2] = quat->q2;
|
||||||
mcu->data.yaw = gimbal_fb->imu.eulr.yaw;
|
mcu->q[3] = quat->q3;
|
||||||
mcu->data.yaw_vel = gimbal_fb->imu.gyro.z;
|
mcu->yaw = gimbal_fb->imu.eulr.yaw;
|
||||||
mcu->data.pitch = gimbal_fb->imu.eulr.pit;
|
mcu->yaw_vel = gimbal_fb->imu.gyro.z;
|
||||||
mcu->data.pitch_vel = gimbal_fb->imu.gyro.x;
|
mcu->pitch = gimbal_fb->imu.eulr.pit;
|
||||||
mcu->data.bullet_speed = bullet_speed;
|
mcu->pitch_vel = gimbal_fb->imu.gyro.x;
|
||||||
mcu->data.bullet_count = bullet_count;
|
mcu->bullet_speed = bullet_speed;
|
||||||
|
mcu->bullet_count = bullet_count;
|
||||||
mcu->crc16 = CRC16_Calc((const uint8_t *)mcu,
|
mcu->crc16 = CRC16_Calc((const uint8_t *)mcu,
|
||||||
sizeof(*mcu) - sizeof(uint16_t), CRC16_INIT);
|
sizeof(*mcu) - sizeof(uint16_t), CRC16_INIT);
|
||||||
if (!CRC16_Verify((const uint8_t *)mcu, sizeof(*mcu))) {
|
if (!CRC16_Verify((const uint8_t *)mcu, sizeof(*mcu))) {
|
||||||
@ -84,13 +77,13 @@ int8_t Aimbot_MCUStartSend(Aimbot_MCU_t *mcu) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
/* =====================================================================
|
/* =====================================================================
|
||||||
* CAN 通信接口(下层板 ↔ 上层板)
|
* CAN 通信接口(下层板 <EFBFBD>?上层板)
|
||||||
* ===================================================================== */
|
* ===================================================================== */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 初始化 Aimbot CAN 通信:注册指令接收队列和反馈收发队列。
|
* @brief 初始<EFBFBD>?Aimbot CAN 通信:注册指令接收队列和反馈收发队列<EFBFBD>?
|
||||||
* 下层板只需注册 cmd_id;上层板只需注册 fb_base_id 的 6 个 ID。
|
* 下层板只需注册 cmd_id;上层板只需注册 fb_base_id <EFBFBD>?6 <EFBFBD>?ID<EFBFBD>?
|
||||||
* 本函数同时注册两侧所需 ID,上/下层板共用同一初始化流程即可。
|
* 本函数同时注册两侧所需 ID,上/下层板共用同一初始化流程即可<EFBFBD>?
|
||||||
*/
|
*/
|
||||||
int8_t Aimbot_Init(Aimbot_Param_t *param) {
|
int8_t Aimbot_Init(Aimbot_Param_t *param) {
|
||||||
if (param == NULL) return DEVICE_ERR_NULL;
|
if (param == NULL) return DEVICE_ERR_NULL;
|
||||||
@ -111,42 +104,27 @@ int8_t Aimbot_Init(Aimbot_Param_t *param) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 从 Gimbal/IMU/Shoot 数据打包 CAN 反馈结构体。
|
* @brief <EFBFBD>?Gimbal/IMU/Shoot 数据打包 CAN 反馈结构体<EFBFBD>?
|
||||||
|
/**
|
||||||
|
* @brief 【下层板】打包 CAN 反馈结构体。
|
||||||
*/
|
*/
|
||||||
int8_t Aimbot_PackFeedback(Aimbot_FeedbackData_t *fb,
|
int8_t Aimbot_PackFeedback(Aimbot_FeedbackData_t *fb,
|
||||||
const Gimbal_Feedback_t *gimbal_fb,
|
|
||||||
const AHRS_Quaternion_t *quat,
|
|
||||||
float bullet_speed, uint16_t bullet_count,
|
float bullet_speed, uint16_t bullet_count,
|
||||||
uint8_t mode) {
|
uint8_t mode) {
|
||||||
if (fb == NULL || gimbal_fb == NULL || quat == NULL) {
|
if (fb == NULL) {
|
||||||
return DEVICE_ERR_NULL;
|
return DEVICE_ERR_NULL;
|
||||||
}
|
}
|
||||||
fb->mode = mode;
|
fb->mode = mode;
|
||||||
fb->q[0] = quat->q0;
|
|
||||||
fb->q[1] = quat->q1;
|
|
||||||
fb->q[2] = quat->q2;
|
|
||||||
fb->q[3] = quat->q3;
|
|
||||||
fb->yaw = gimbal_fb->imu.eulr.yaw;
|
|
||||||
fb->pitch = gimbal_fb->imu.eulr.pit;
|
|
||||||
fb->yaw_vel = gimbal_fb->imu.gyro.z;
|
|
||||||
fb->pitch_vel = gimbal_fb->imu.gyro.x;
|
|
||||||
fb->bullet_speed = bullet_speed;
|
fb->bullet_speed = bullet_speed;
|
||||||
fb->bullet_count = bullet_count;
|
fb->bullet_count = bullet_count;
|
||||||
fb->gimbal_yaw = gimbal_fb->motor.yaw.rotor_abs_angle;
|
|
||||||
fb->gimbal_pit = gimbal_fb->motor.pit.rotor_abs_angle;
|
|
||||||
return DEVICE_OK;
|
return DEVICE_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 【下层板】将反馈数据打成 6 个 CAN 标准帧发给上层板。
|
* @brief 【下层板】将反馈数据打成 1 个 CAN 标准帧发给上层板。
|
||||||
*
|
*
|
||||||
* 帧格式(每帧 8 字节):
|
* 帧格式(每帧 8 字节):
|
||||||
* 帧0: q[0](float,4B) q[1](float,4B)
|
* 帧0: bullet_speed(float,4B) bullet_count(uint16,2B) mode(1B) rsv(1B)
|
||||||
* 帧1: q[2](float,4B) q[3](float,4B)
|
|
||||||
* 帧2: yaw(float,4B) pitch(float,4B)
|
|
||||||
* 帧3: yaw_vel(float,4B) pitch_vel(float,4B)
|
|
||||||
* 帧4: bullet_speed(float,4B) bullet_count(uint16,2B) mode(1B) rsv(1B)
|
|
||||||
* 帧5: gimbal_yaw(float,4B) gimbal_pit(float,4B)
|
|
||||||
*/
|
*/
|
||||||
void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
||||||
const Aimbot_FeedbackData_t *fb) {
|
const Aimbot_FeedbackData_t *fb) {
|
||||||
@ -155,53 +133,23 @@ void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
|||||||
BSP_FDCAN_StdDataFrame_t frame;
|
BSP_FDCAN_StdDataFrame_t frame;
|
||||||
frame.dlc = AIMBOT_CAN_DLC;
|
frame.dlc = AIMBOT_CAN_DLC;
|
||||||
|
|
||||||
/* 帧0: IMU 四元数 q[0], q[1] */
|
/* 帧0: 弹速 + 弹数 + 模式 */
|
||||||
frame.id = param->fb_base_id + FB_FRAME_Q01;
|
frame.id = param->fb_base_id + FB_FRAME_DATA;
|
||||||
memcpy(&frame.data[0], &fb->q[0], 4);
|
|
||||||
memcpy(&frame.data[4], &fb->q[1], 4);
|
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
|
||||||
|
|
||||||
/* 帧1: IMU 四元数 q[2], q[3] */
|
|
||||||
frame.id = param->fb_base_id + FB_FRAME_Q23;
|
|
||||||
memcpy(&frame.data[0], &fb->q[2], 4);
|
|
||||||
memcpy(&frame.data[4], &fb->q[3], 4);
|
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
|
||||||
|
|
||||||
/* 帧2: IMU 欧拉角 yaw, pitch */
|
|
||||||
frame.id = param->fb_base_id + FB_FRAME_EULR;
|
|
||||||
memcpy(&frame.data[0], &fb->yaw, 4);
|
|
||||||
memcpy(&frame.data[4], &fb->pitch, 4);
|
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
|
||||||
|
|
||||||
/* 帧3: IMU 角速度 yaw_vel, pitch_vel */
|
|
||||||
frame.id = param->fb_base_id + FB_FRAME_VEL;
|
|
||||||
memcpy(&frame.data[0], &fb->yaw_vel, 4);
|
|
||||||
memcpy(&frame.data[4], &fb->pitch_vel, 4);
|
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
|
||||||
|
|
||||||
/* 帧4: 弹速 + 弹数 + 模式 */
|
|
||||||
frame.id = param->fb_base_id + FB_FRAME_SHOOT;
|
|
||||||
memcpy(&frame.data[0], &fb->bullet_speed, 4);
|
memcpy(&frame.data[0], &fb->bullet_speed, 4);
|
||||||
frame.data[4] = (uint8_t)(fb->bullet_count & 0xFFu);
|
frame.data[4] = (uint8_t)(fb->bullet_count & 0xFFu);
|
||||||
frame.data[5] = (uint8_t)((fb->bullet_count >> 8u) & 0xFFu);
|
frame.data[5] = (uint8_t)((fb->bullet_count >> 8u) & 0xFFu);
|
||||||
frame.data[6] = fb->mode;
|
frame.data[6] = fb->mode;
|
||||||
frame.data[7] = 0u;
|
frame.data[7] = 0u;
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
||||||
|
|
||||||
/* 帧5: 云台电机绝对角度 yaw, pit */
|
|
||||||
frame.id = param->fb_base_id + FB_FRAME_MOTOR;
|
|
||||||
memcpy(&frame.data[0], &fb->gimbal_yaw, 4);
|
|
||||||
memcpy(&frame.data[4], &fb->gimbal_pit, 4);
|
|
||||||
BSP_FDCAN_TransmitStdDataFrame(param->can, &frame);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 【下层板】从 CAN 队列中非阻塞地取出上层板发来的 AI 指令并解析。
|
* @brief 【下层板】从 CAN 队列中非阻塞地取出上层板发来<EFBFBD>?AI 指令并解析<EFBFBD>?
|
||||||
*
|
*
|
||||||
* 指令帧格式(8 字节,与 vision_bridge 一致):
|
* 指令帧格式(8 字节,与 vision_bridge 一致)<EFBFBD>?
|
||||||
* data[0] : mode (1B)
|
* data[0] : mode (1B)
|
||||||
* data[1..3.5] : yaw (28bit 有符号定点数,0.1µrad/LSB)
|
* data[1..3.5] : yaw (28bit 有符号定点数<EFBFBD>?.1µrad/LSB)
|
||||||
* data[4.5..7] : pit (28bit 有符号定点数,0.1µrad/LSB)
|
* data[4.5..7] : pit (28bit 有符号定点数<EFBFBD>?.1µrad/LSB)
|
||||||
*
|
*
|
||||||
* @return DEVICE_OK 成功解析到新指令
|
* @return DEVICE_OK 成功解析到新指令
|
||||||
* DEVICE_ERR 队列空,无新数据
|
* DEVICE_ERR 队列空,无新数据
|
||||||
@ -234,7 +182,7 @@ int8_t Aimbot_ParseCmdFromCAN(const Aimbot_Param_t *param,
|
|||||||
if (pit_raw & 0x08000000) pit_raw |= (int32_t)0xF0000000;
|
if (pit_raw & 0x08000000) pit_raw |= (int32_t)0xF0000000;
|
||||||
result->gimbal_t.setpoint.pit = (float)pit_raw / AIMBOT_ANGLE_SCALE;
|
result->gimbal_t.setpoint.pit = (float)pit_raw / AIMBOT_ANGLE_SCALE;
|
||||||
|
|
||||||
/* 速度/加速度前馈由上层板另行扩展,此处置零 */
|
/* 速度/加速度前馈由上层板另行扩展,此处置<EFBFBD>?*/
|
||||||
result->gimbal_t.vel.yaw = 0.0f;
|
result->gimbal_t.vel.yaw = 0.0f;
|
||||||
result->gimbal_t.vel.pit = 0.0f;
|
result->gimbal_t.vel.pit = 0.0f;
|
||||||
result->gimbal_t.accl.yaw = 0.0f;
|
result->gimbal_t.accl.yaw = 0.0f;
|
||||||
@ -244,10 +192,10 @@ int8_t Aimbot_ParseCmdFromCAN(const Aimbot_Param_t *param,
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 【上层板】将 AI 指令通过 CAN 发送给下层板(单帧 8 字节)。
|
* @brief 【上层板】将 AI 指令通过 CAN 发送给下层板(单帧 8 字节)<EFBFBD>?
|
||||||
*
|
*
|
||||||
* 与 vision_bridge.c 的 AI_SendCmdOnFDCAN 编码格式完全一致,
|
* <EFBFBD>?vision_bridge.c <EFBFBD>?AI_SendCmdOnFDCAN 编码格式完全一致,
|
||||||
* 上层板可直接调用本函数替代 vision_bridge 中的同名函数。
|
* 上层板可直接调用本函数替<EFBFBD>?vision_bridge 中的同名函数<EFBFBD>?
|
||||||
*/
|
*/
|
||||||
void Aimbot_SendCmdOnCAN(const Aimbot_Param_t *param,
|
void Aimbot_SendCmdOnCAN(const Aimbot_Param_t *param,
|
||||||
const Aimbot_AIResult_t *cmd) {
|
const Aimbot_AIResult_t *cmd) {
|
||||||
@ -273,10 +221,9 @@ void Aimbot_SendCmdOnCAN(const Aimbot_Param_t *param,
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 【上层板】从 CAN 队列中逐帧非阻塞地解析下层板发来的反馈数据。
|
* @brief 【上层板】从 CAN 队列中非阻塞地解析下层板发来的反馈数据(共1帧)。
|
||||||
* 各帧独立读取,缺失的帧保留上一次的旧值,不影响其他帧。
|
|
||||||
*
|
*
|
||||||
* @return DEVICE_OK(始终返回,允许部分帧缺失)
|
* @return DEVICE_OK
|
||||||
*/
|
*/
|
||||||
int8_t Aimbot_ParseFeedbackFromCAN(const Aimbot_Param_t *param,
|
int8_t Aimbot_ParseFeedbackFromCAN(const Aimbot_Param_t *param,
|
||||||
Aimbot_FeedbackData_t *fb) {
|
Aimbot_FeedbackData_t *fb) {
|
||||||
@ -284,55 +231,15 @@ int8_t Aimbot_ParseFeedbackFromCAN(const Aimbot_Param_t *param,
|
|||||||
|
|
||||||
BSP_FDCAN_Message_t msg;
|
BSP_FDCAN_Message_t msg;
|
||||||
|
|
||||||
/* 帧0: IMU 四元数 q[0], q[1] */
|
/* 帧0: 弹速 + 弹数 + 模式 */
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
if (BSP_FDCAN_GetMessage(param->can,
|
||||||
param->fb_base_id + FB_FRAME_Q01,
|
param->fb_base_id + FB_FRAME_DATA,
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
|
||||||
memcpy(&fb->q[0], &msg.data[0], 4);
|
|
||||||
memcpy(&fb->q[1], &msg.data[4], 4);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* 帧1: IMU 四元数 q[2], q[3] */
|
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
|
||||||
param->fb_base_id + FB_FRAME_Q23,
|
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
|
||||||
memcpy(&fb->q[2], &msg.data[0], 4);
|
|
||||||
memcpy(&fb->q[3], &msg.data[4], 4);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* 帧2: IMU 欧拉角 yaw, pitch */
|
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
|
||||||
param->fb_base_id + FB_FRAME_EULR,
|
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
|
||||||
memcpy(&fb->yaw, &msg.data[0], 4);
|
|
||||||
memcpy(&fb->pitch, &msg.data[4], 4);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* 帧3: IMU 角速度 yaw_vel, pitch_vel */
|
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
|
||||||
param->fb_base_id + FB_FRAME_VEL,
|
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
|
||||||
memcpy(&fb->yaw_vel, &msg.data[0], 4);
|
|
||||||
memcpy(&fb->pitch_vel, &msg.data[4], 4);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* 帧4: 弹速 + 弹数 + 模式 */
|
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
|
||||||
param->fb_base_id + FB_FRAME_SHOOT,
|
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
||||||
memcpy(&fb->bullet_speed, &msg.data[0], 4);
|
memcpy(&fb->bullet_speed, &msg.data[0], 4);
|
||||||
fb->bullet_count = (uint16_t)(msg.data[4] | ((uint16_t)msg.data[5] << 8u));
|
fb->bullet_count = (uint16_t)(msg.data[4] | ((uint16_t)msg.data[5] << 8u));
|
||||||
fb->mode = msg.data[6];
|
fb->mode = msg.data[6];
|
||||||
}
|
}
|
||||||
|
|
||||||
/* 帧5: 云台电机绝对角度 yaw, pit */
|
|
||||||
if (BSP_FDCAN_GetMessage(param->can,
|
|
||||||
param->fb_base_id + FB_FRAME_MOTOR,
|
|
||||||
&msg, BSP_FDCAN_TIMEOUT_IMMEDIATE) == 0) {
|
|
||||||
memcpy(&fb->gimbal_yaw, &msg.data[0], 4);
|
|
||||||
memcpy(&fb->gimbal_pit, &msg.data[4], 4);
|
|
||||||
}
|
|
||||||
|
|
||||||
return DEVICE_OK;
|
return DEVICE_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@ -7,31 +7,24 @@ extern "C" {
|
|||||||
|
|
||||||
/* Includes ----------------------------------------------------------------- */
|
/* Includes ----------------------------------------------------------------- */
|
||||||
#include "component\user_math.h"
|
#include "component\user_math.h"
|
||||||
// #include "remote_control.h"
|
|
||||||
#include "module/gimbal.h"
|
#include "module/gimbal.h"
|
||||||
#include "bsp/fdcan.h"
|
#include "bsp/fdcan.h"
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
// 数据包 ID 定义
|
// 数据包协议定义(UART 通信使用 head[2]={'M', 'R'} 标识)
|
||||||
#define ID_MCU (0xC4) // MCU 数据包
|
|
||||||
#define ID_REF (0xA8) // 裁判系统数据包
|
|
||||||
#define ID_AI (0xB5) // AI 控制数据包
|
|
||||||
|
|
||||||
/* ============================ CAN 通信定义 ============================
|
/* ============================ CAN 通信定义 ============================
|
||||||
* 通路:上位机 <--串口--> 上层板 <--CAN--> 下层板(本代码)
|
* 通路:上位机 <--串口--> 上层板 <--CAN--> 下层板
|
||||||
*
|
*
|
||||||
* 下层板 → 上层板:反馈数据,共 AIMBOT_FB_FRAME_NUM 帧,CAN ID 连续
|
* 注:上层板使用自己的IMU(atti_esti),下层板只需反馈电机和射击数据
|
||||||
* 帧0 (fb_base_id+0): IMU 四元数 q[0], q[1]
|
*
|
||||||
* 帧1 (fb_base_id+1): IMU 四元数 q[2], q[3]
|
* 下层板 → 上层板:反馈数据,单帧 8 字节
|
||||||
* 帧2 (fb_base_id+2): IMU 欧拉角 yaw, pitch (rad)
|
* 帧0 (fb_base_id+0): 弹速(4B) + 弹数(2B) + 模式(1B) + 保留(1B)
|
||||||
* 帧3 (fb_base_id+3): IMU 角速度 yaw_vel, pitch_vel (rad/s)
|
|
||||||
* 帧4 (fb_base_id+4): 弹速(4B) + 弹数(2B) + 模式(1B) + 保留(1B)
|
|
||||||
* 帧5 (fb_base_id+5): 云台电机绝对角度 yaw, pit (rad)
|
|
||||||
*
|
*
|
||||||
* 上层板 → 下层板:AI 指令,单帧 8 字节
|
* 上层板 → 下层板:AI 指令,单帧 8 字节
|
||||||
* 帧 (cmd_id): mode(1B) + yaw(28bit) + pit(28bit),定点数精度 0.1µrad
|
* 帧 (cmd_id): mode(1B) + yaw(28bit) + pit(28bit),定点数精度 0.1µrad
|
||||||
* ====================================================================== */
|
* ====================================================================== */
|
||||||
#define AIMBOT_FB_FRAME_NUM 6u /* 反馈数据帧总数 */
|
#define AIMBOT_FB_FRAME_NUM 1u /* 反馈数据帧总数(仅下层三字段) */
|
||||||
#define AIMBOT_CAN_DLC 8u /* CAN 帧数据长度 */
|
#define AIMBOT_CAN_DLC 8u /* CAN 帧数据长度 */
|
||||||
#define AIMBOT_ANGLE_SCALE 10000000.0f /* 指令角度定点数比例(0.1µrad/LSB) */
|
#define AIMBOT_ANGLE_SCALE 10000000.0f /* 指令角度定点数比例(0.1µrad/LSB) */
|
||||||
|
|
||||||
@ -39,26 +32,21 @@ extern "C" {
|
|||||||
typedef struct {
|
typedef struct {
|
||||||
BSP_FDCAN_t can; /* 使用的 CAN 总线实例 */
|
BSP_FDCAN_t can; /* 使用的 CAN 总线实例 */
|
||||||
uint32_t cmd_id; /* 上层板→下层板 AI 指令帧 CAN ID */
|
uint32_t cmd_id; /* 上层板→下层板 AI 指令帧 CAN ID */
|
||||||
uint32_t fb_base_id; /* 下层板→上层板 反馈数据起始 CAN ID(共6帧,ID连续递增) */
|
uint32_t fb_base_id; /* 下层板→上层板 反馈数据起始 CAN ID */
|
||||||
} Aimbot_Param_t;
|
} Aimbot_Param_t;
|
||||||
|
|
||||||
/* CAN 反馈数据结构体(下层板打包后经 CAN 发给上层板的内容) */
|
/* CAN 反馈数据结构体(下层板打包后经 CAN 发给上层板的内容)
|
||||||
|
* 注:下层板只反馈 bullet_speed / bullet_count / mode */
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t mode; /* 下层板当前工作模式 */
|
uint8_t mode; /* 下层板当前工作模式 */
|
||||||
float q[4]; /* IMU 四元数 q0(w) q1(x) q2(y) q3(z) */
|
|
||||||
float yaw; /* IMU yaw 角(rad) */
|
|
||||||
float yaw_vel; /* IMU yaw 角速度(rad/s) */
|
|
||||||
float pitch; /* IMU pitch 角(rad) */
|
|
||||||
float pitch_vel; /* IMU pitch 角速度(rad/s) */
|
|
||||||
float bullet_speed; /* 弹速(m/s) */
|
float bullet_speed; /* 弹速(m/s) */
|
||||||
uint16_t bullet_count; /* 子弹累计发射次数 */
|
uint16_t bullet_count; /* 子弹累计发射次数 */
|
||||||
float gimbal_yaw; /* 云台 yaw 电机绝对角度(rad) */
|
|
||||||
float gimbal_pit; /* 云台 pitch 电机绝对角度(rad) */
|
|
||||||
} Aimbot_FeedbackData_t;
|
} Aimbot_FeedbackData_t;
|
||||||
|
|
||||||
/*-----------------------------to上位机---------------------------------*/
|
/*-----------------------------to上位机---------------------------------*/
|
||||||
typedef struct __attribute__((packed))
|
typedef struct __attribute__((packed))
|
||||||
{
|
{
|
||||||
|
uint8_t head[2]; // 数据包头: {'M', 'R'}
|
||||||
uint8_t mode; // 0: 空闲, 1: 自瞄, 2: 小符, 3: 大符
|
uint8_t mode; // 0: 空闲, 1: 自瞄, 2: 小符, 3: 大符
|
||||||
float q[4]; // 四元数 wxyz 顺序
|
float q[4]; // 四元数 wxyz 顺序
|
||||||
float yaw; // 偏航角
|
float yaw; // 偏航角
|
||||||
@ -67,13 +55,7 @@ typedef struct __attribute__((packed))
|
|||||||
float pitch_vel; // 俯仰角速度
|
float pitch_vel; // 俯仰角速度
|
||||||
float bullet_speed; // 弹速
|
float bullet_speed; // 弹速
|
||||||
uint16_t bullet_count; // 子弹累计发送次数
|
uint16_t bullet_count; // 子弹累计发送次数
|
||||||
} Aimbot_MCUData_t;
|
uint16_t crc16; // CRC16 校验
|
||||||
|
|
||||||
typedef struct __attribute__((packed))
|
|
||||||
{
|
|
||||||
uint8_t id; // 数据包 ID: 0xC4
|
|
||||||
Aimbot_MCUData_t data;
|
|
||||||
uint16_t crc16;
|
|
||||||
} Aimbot_MCU_t;
|
} Aimbot_MCU_t;
|
||||||
|
|
||||||
// 裁判系统数据结构
|
// 裁判系统数据结构
|
||||||
@ -94,24 +76,15 @@ typedef struct __attribute__((packed))
|
|||||||
/*------------------------------------上位机back-------------------------------------*/
|
/*------------------------------------上位机back-------------------------------------*/
|
||||||
typedef struct __attribute__((packed))
|
typedef struct __attribute__((packed))
|
||||||
{
|
{
|
||||||
uint8_t mode; // 0: 不控制, 1: 控制云台但不开火, 2: 控制云台且开火
|
uint8_t head[2]; // 数据包头: {'M', 'R'}
|
||||||
|
uint8_t mode; // 0: 不控制, 1: 控制云台但不开火,2: 控制云台且开火
|
||||||
float yaw; // 目标偏航角
|
float yaw; // 目标偏航角
|
||||||
float yaw_vel; // 偏航角速度
|
float yaw_vel; // 偏航角速度
|
||||||
float yaw_acc; // 偏航角加速度
|
float yaw_acc; // 偏航角加速度
|
||||||
float pitch; // 目标俯仰角
|
float pitch; // 目标俯仰角
|
||||||
float pitch_vel; // 俯仰角速度
|
float pitch_vel; // 俯仰角速度
|
||||||
float pitch_acc; // 俯仰角加速度
|
float pitch_acc; // 俯仰角加速度
|
||||||
float vx; // X 方向速度
|
uint16_t crc16; // CRC16 校验
|
||||||
float vy; // Y 方向速度
|
|
||||||
float wz; // Z 方向角速度
|
|
||||||
uint8_t reserved; // 预留字段
|
|
||||||
} Aimbot_AIData_t;
|
|
||||||
|
|
||||||
typedef struct __attribute__((packed))
|
|
||||||
{
|
|
||||||
uint8_t id; // 数据包 ID: 0xB5
|
|
||||||
Aimbot_AIData_t data;
|
|
||||||
uint16_t crc16;
|
|
||||||
} Aimbot_AI_t;
|
} Aimbot_AI_t;
|
||||||
|
|
||||||
typedef struct __attribute__((packed)) {
|
typedef struct __attribute__((packed)) {
|
||||||
@ -145,7 +118,7 @@ typedef struct __attribute__((packed)) {
|
|||||||
/* ---------- UART 通信接口(上层板与上位机 PC 间) ---------- */
|
/* ---------- UART 通信接口(上层板与上位机 PC 间) ---------- */
|
||||||
int8_t Aimbot_MCUPack(Aimbot_MCU_t *mcu, const Gimbal_Feedback_t *gimbal_fb,
|
int8_t Aimbot_MCUPack(Aimbot_MCU_t *mcu, const Gimbal_Feedback_t *gimbal_fb,
|
||||||
const AHRS_Quaternion_t *quat,
|
const AHRS_Quaternion_t *quat,
|
||||||
float bullet_speed, uint16_t bullet_count);
|
float bullet_speed, uint16_t bullet_count, uint8_t mode);
|
||||||
int8_t Aimbot_MCUStartSend(Aimbot_MCU_t *mcu);
|
int8_t Aimbot_MCUStartSend(Aimbot_MCU_t *mcu);
|
||||||
int8_t Aimbot_AIGetResult(Aimbot_AI_t *ai, Aimbot_AIResult_t *result);
|
int8_t Aimbot_AIGetResult(Aimbot_AI_t *ai, Aimbot_AIResult_t *result);
|
||||||
int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai);
|
int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai);
|
||||||
@ -160,22 +133,18 @@ int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai);
|
|||||||
int8_t Aimbot_Init(Aimbot_Param_t *param);
|
int8_t Aimbot_Init(Aimbot_Param_t *param);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 从 Gimbal/IMU/Shoot 数据中打包反馈结构体
|
* @brief 【下层板】打包反馈结构体
|
||||||
* @param fb 输出:反馈数据
|
* @param fb 输出:反馈数据
|
||||||
* @param gimbal_fb 云台反馈(含 IMU 欧拉角/角速度、电机角度)
|
|
||||||
* @param quat IMU 四元数
|
|
||||||
* @param bullet_speed 弹速(m/s)
|
* @param bullet_speed 弹速(m/s)
|
||||||
* @param bullet_count 已发射子弹数
|
* @param bullet_count 已发射子弹数
|
||||||
* @param mode 当前工作模式
|
* @param mode 当前工作模式
|
||||||
*/
|
*/
|
||||||
int8_t Aimbot_PackFeedback(Aimbot_FeedbackData_t *fb,
|
int8_t Aimbot_PackFeedback(Aimbot_FeedbackData_t *fb,
|
||||||
const Gimbal_Feedback_t *gimbal_fb,
|
|
||||||
const AHRS_Quaternion_t *quat,
|
|
||||||
float bullet_speed, uint16_t bullet_count,
|
float bullet_speed, uint16_t bullet_count,
|
||||||
uint8_t mode);
|
uint8_t mode);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief 【下层板】将反馈数据经 CAN 发送给上层板(6 帧)
|
* @brief 【下层板】将反馈数据经 CAN 发送给上层板(1 帧)
|
||||||
*/
|
*/
|
||||||
void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
||||||
const Aimbot_FeedbackData_t *fb);
|
const Aimbot_FeedbackData_t *fb);
|
||||||
|
|||||||
@ -42,7 +42,6 @@ static void CMD_RC_BuildChassisCmd(CMD_t *ctx) {
|
|||||||
#if CMD_ENABLE_SRC_RC && CMD_ENABLE_MODULE_GIMBAL
|
#if CMD_ENABLE_SRC_RC && CMD_ENABLE_MODULE_GIMBAL
|
||||||
static void CMD_RC_BuildGimbalCmd(CMD_t *ctx) {
|
static void CMD_RC_BuildGimbalCmd(CMD_t *ctx) {
|
||||||
CMD_RCModeMap_t *map = &ctx->config->rc_mode_map;
|
CMD_RCModeMap_t *map = &ctx->config->rc_mode_map;
|
||||||
ctx->output.gimbal.cmd.is_ai = false;
|
|
||||||
/* 根据拨杆选择云台模式 */
|
/* 根据拨杆选择云台模式 */
|
||||||
switch (ctx->input.rc.sw[0]) {
|
switch (ctx->input.rc.sw[0]) {
|
||||||
case CMD_SW_UP:
|
case CMD_SW_UP:
|
||||||
@ -156,7 +155,6 @@ static void CMD_PC_BuildGimbalCmd(CMD_t *ctx) {
|
|||||||
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_RELAX;
|
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_RELAX;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
ctx->output.gimbal.cmd.is_ai = false;
|
|
||||||
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_ABSOLUTE;
|
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_ABSOLUTE;
|
||||||
|
|
||||||
/* 鼠标控制云台 */
|
/* 鼠标控制云台 */
|
||||||
@ -211,7 +209,6 @@ static void CMD_NUC_BuildGimbalCmd(CMD_t *ctx) {
|
|||||||
|
|
||||||
/* 使用AI提供的云台控制数据 */
|
/* 使用AI提供的云台控制数据 */
|
||||||
|
|
||||||
if (ctx->input.nuc.mode!=0) {
|
|
||||||
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_AI_CONTROL;
|
ctx->output.gimbal.cmd.mode = GIMBAL_MODE_AI_CONTROL;
|
||||||
ctx->output.gimbal.cmd.setpoint_yaw = ctx->input.nuc.gimbal.setpoint.yaw;
|
ctx->output.gimbal.cmd.setpoint_yaw = ctx->input.nuc.gimbal.setpoint.yaw;
|
||||||
ctx->output.gimbal.cmd.setpoint_pit = ctx->input.nuc.gimbal.setpoint.pit;
|
ctx->output.gimbal.cmd.setpoint_pit = ctx->input.nuc.gimbal.setpoint.pit;
|
||||||
@ -219,7 +216,7 @@ static void CMD_NUC_BuildGimbalCmd(CMD_t *ctx) {
|
|||||||
ctx->output.gimbal.cmd.ff_vel_pit = ctx->input.nuc.gimbal.vel.pit;
|
ctx->output.gimbal.cmd.ff_vel_pit = ctx->input.nuc.gimbal.vel.pit;
|
||||||
ctx->output.gimbal.cmd.ff_accl_yaw = ctx->input.nuc.gimbal.accl.yaw;
|
ctx->output.gimbal.cmd.ff_accl_yaw = ctx->input.nuc.gimbal.accl.yaw;
|
||||||
ctx->output.gimbal.cmd.ff_accl_pit = ctx->input.nuc.gimbal.accl.pit;
|
ctx->output.gimbal.cmd.ff_accl_pit = ctx->input.nuc.gimbal.accl.pit;
|
||||||
}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif /* CMD_ENABLE_SRC_NUC && CMD_ENABLE_MODULE_GIMBAL */
|
#endif /* CMD_ENABLE_SRC_NUC && CMD_ENABLE_MODULE_GIMBAL */
|
||||||
|
|||||||
@ -7,7 +7,7 @@
|
|||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include "cmd_feature.h" /* 功能特性开关 */
|
#include "cmd_feature.h" /* 功能特性开关 */
|
||||||
#include "device/referee_proto_types.h" /* 裁判转发包基础类型(叶节点,无循环依赖) */
|
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C" {
|
extern "C" {
|
||||||
@ -192,6 +192,7 @@ typedef struct {
|
|||||||
} CMD_RawInput_NUC_t;
|
} CMD_RawInput_NUC_t;
|
||||||
|
|
||||||
#if CMD_ENABLE_SRC_REF
|
#if CMD_ENABLE_SRC_REF
|
||||||
|
#include "device/referee_proto_types.h"
|
||||||
/* 裁判系统原始输入,包含需转发给各模块的完整子集 */
|
/* 裁判系统原始输入,包含需转发给各模块的完整子集 */
|
||||||
typedef struct {
|
typedef struct {
|
||||||
Referee_ForChassis_t chassis;
|
Referee_ForChassis_t chassis;
|
||||||
|
|||||||
@ -29,11 +29,9 @@ Config_RobotParam_t robot_config = {
|
|||||||
.vision_id = 0x104,
|
.vision_id = 0x104,
|
||||||
},
|
},
|
||||||
.aimbot_param = {
|
.aimbot_param = {
|
||||||
/* 下层板接收AI指令帧 ID(上层板发→下层板收) */
|
|
||||||
.can = BSP_FDCAN_2,
|
.can = BSP_FDCAN_2,
|
||||||
.cmd_id = 0x250u,
|
.cmd_id = 0x520u,
|
||||||
/* 下层板反馈帧起始 ID(占连续6个ID:0x251-0x256) */
|
.fb_base_id = 0x521u,
|
||||||
.fb_base_id = 0x251u,
|
|
||||||
},
|
},
|
||||||
.imu_param = {
|
.imu_param = {
|
||||||
.can=BSP_FDCAN_2,
|
.can=BSP_FDCAN_2,
|
||||||
@ -418,7 +416,7 @@ Config_RobotParam_t robot_config = {
|
|||||||
.sw_left_down = CHASSIS_MODE_RELAX,
|
.sw_left_down = CHASSIS_MODE_RELAX,
|
||||||
.gimbal_sw_up = GIMBAL_MODE_ABSOLUTE,
|
.gimbal_sw_up = GIMBAL_MODE_ABSOLUTE,
|
||||||
.gimbal_sw_mid = GIMBAL_MODE_RELATIVE,
|
.gimbal_sw_mid = GIMBAL_MODE_RELATIVE,
|
||||||
.gimbal_sw_down = GIMBAL_MODE_ABSOLUTE,
|
.gimbal_sw_down = GIMBAL_MODE_AI_CONTROL,
|
||||||
.track_sw_up = false,
|
.track_sw_up = false,
|
||||||
.track_sw_mid = true,
|
.track_sw_mid = true,
|
||||||
.track_sw_down = false,
|
.track_sw_down = false,
|
||||||
|
|||||||
@ -57,8 +57,8 @@ static int8_t Gimbal_SetMode(Gimbal_t *g, Gimbal_Mode_t mode) {
|
|||||||
} else if (mode == GIMBAL_MODE_RELATIVE) {
|
} else if (mode == GIMBAL_MODE_RELATIVE) {
|
||||||
g->setpoint.eulr.yaw = g->feedback.imu.eulr.yaw;
|
g->setpoint.eulr.yaw = g->feedback.imu.eulr.yaw;
|
||||||
} else if (mode == GIMBAL_MODE_AI_CONTROL) {
|
} else if (mode == GIMBAL_MODE_AI_CONTROL) {
|
||||||
g->setpoint.eulr.yaw = g->feedback.motor.yaw.rotor_abs_angle;
|
g->setpoint.eulr.yaw = g->feedback.imu.eulr.yaw;
|
||||||
g->setpoint.eulr.pit = g->feedback.motor.pit.rotor_abs_angle;
|
g->setpoint.eulr.pit =g->feedback.imu.eulr.pit;
|
||||||
}
|
}
|
||||||
|
|
||||||
g->mode = mode;
|
g->mode = mode;
|
||||||
@ -244,9 +244,6 @@ int8_t Gimbal_Control(Gimbal_t *g, Gimbal_CMD_t *g_cmd) {
|
|||||||
/* AI 模式:直接从指令获取角度设定值(每周期刷新) */
|
/* AI 模式:直接从指令获取角度设定值(每周期刷新) */
|
||||||
g->setpoint.eulr.yaw = g_cmd->setpoint_yaw;
|
g->setpoint.eulr.yaw = g_cmd->setpoint_yaw;
|
||||||
g->setpoint.eulr.pit = g_cmd->setpoint_pit;
|
g->setpoint.eulr.pit = g_cmd->setpoint_pit;
|
||||||
} else if (g_cmd->is_ai) {
|
|
||||||
g->setpoint.eulr.yaw = g_cmd->setpoint_yaw;
|
|
||||||
g->setpoint.eulr.pit = g_cmd->setpoint_pit;
|
|
||||||
}
|
}
|
||||||
/* 控制相关逻辑 */
|
/* 控制相关逻辑 */
|
||||||
float yaw_omega_set_point, pit_omega_set_point;
|
float yaw_omega_set_point, pit_omega_set_point;
|
||||||
|
|||||||
@ -522,7 +522,9 @@ int8_t Shoot_CaluTargetAngle(Shoot_t *s, Shoot_CMD_t *cmd)
|
|||||||
s->var_trig.time_lastShoot=s->timer.now;
|
s->var_trig.time_lastShoot=s->timer.now;
|
||||||
CircleAdd(&s->target_variable.trig_angle, M_2PI/s->param->basic.num_trig_tooth, M_2PI);
|
CircleAdd(&s->target_variable.trig_angle, M_2PI/s->param->basic.num_trig_tooth, M_2PI);
|
||||||
s->var_trig.num_toShoot--;
|
s->var_trig.num_toShoot--;
|
||||||
|
s->var_trig.num_shooted++;
|
||||||
}
|
}
|
||||||
|
|
||||||
return SHOOT_OK;
|
return SHOOT_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -967,7 +969,7 @@ int8_t Shoot_Control(Shoot_t *s, Shoot_CMD_t *cmd)
|
|||||||
Shoot_CaluTargetRPM(s,233);
|
Shoot_CaluTargetRPM(s,233);
|
||||||
|
|
||||||
/* 运行热量检测状态机 */
|
/* 运行热量检测状态机 */
|
||||||
Shoot_HeatDetectionFSM(s);
|
// Shoot_HeatDetectionFSM(s);
|
||||||
|
|
||||||
/* 运行卡弹检测状态机 */
|
/* 运行卡弹检测状态机 */
|
||||||
Shoot_JamDetectionFSM(s, cmd);
|
Shoot_JamDetectionFSM(s, cmd);
|
||||||
@ -986,3 +988,7 @@ void Shoot_DumpUI(Shoot_t *s, Shoot_RefereeUI_t *ui) {
|
|||||||
ui->fire = s->running_state;
|
ui->fire = s->running_state;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void Shoot_DumpAI(Shoot_t *s, Shoot_AI_t *ai) {
|
||||||
|
ai->num_shooted=s->var_trig.num_shooted;
|
||||||
|
ai->bullet_speed=12.0f;
|
||||||
|
}
|
||||||
|
|||||||
@ -51,6 +51,11 @@ typedef enum {
|
|||||||
SHOOT_MODE_NUM
|
SHOOT_MODE_NUM
|
||||||
}Shoot_Mode_t;
|
}Shoot_Mode_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint16_t num_shooted;/* 已发射弹数 */
|
||||||
|
float bullet_speed;/* 目标弹速 */
|
||||||
|
}Shoot_AI_t;
|
||||||
|
|
||||||
/* UI 导出结构(供 referee 系统绘制) */
|
/* UI 导出结构(供 referee 系统绘制) */
|
||||||
typedef struct {
|
typedef struct {
|
||||||
Shoot_Mode_t mode;
|
Shoot_Mode_t mode;
|
||||||
@ -216,6 +221,7 @@ typedef struct {
|
|||||||
struct {
|
struct {
|
||||||
float fric_rpm; /* 目标摩擦轮转速 */
|
float fric_rpm; /* 目标摩擦轮转速 */
|
||||||
float trig_angle;/* 目标拨弹位置 */
|
float trig_angle;/* 目标拨弹位置 */
|
||||||
|
float bullet_speed;/* 目标弹速 */
|
||||||
}target_variable;
|
}target_variable;
|
||||||
|
|
||||||
/* 反馈控制用的PID */
|
/* 反馈控制用的PID */
|
||||||
@ -292,7 +298,7 @@ int8_t Shoot_Control(Shoot_t *s, Shoot_CMD_t *cmd);
|
|||||||
*/
|
*/
|
||||||
void Shoot_DumpUI(Shoot_t *s, Shoot_RefereeUI_t *ui);
|
void Shoot_DumpUI(Shoot_t *s, Shoot_RefereeUI_t *ui);
|
||||||
|
|
||||||
|
void Shoot_DumpAI(Shoot_t *s, Shoot_AI_t *ai) ;
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@ -1,10 +1,12 @@
|
|||||||
/*
|
/*
|
||||||
ai Task
|
AI Task - 下层板
|
||||||
通路:上位机 <--串口--> 上层板 <--CAN--> 下层板(本文件)
|
数据链路:
|
||||||
下层板职责:
|
上层板 <--CAN--> 下层板(本板)
|
||||||
1. 将云台/IMU 反馈数据通过 CAN 发送给上层板
|
流程:
|
||||||
2. 从 CAN 解析上层板转发的 AI 控制指令
|
1. 从消息队列获取本板 射击反馈数据/裁判系统等数据
|
||||||
3. 将解析结果写入 cmd.nuc 队列供 cmd task 消费
|
2. 打包弹速、弹数、模式,通过CAN发给上层板 (Aimbot_SendFeedbackOnCAN)
|
||||||
|
3. 从 CAN 接收上层板下发的 AI 指令 (Aimbot_ParseCmdFromCAN)
|
||||||
|
4. 将解析后的 AI 指令发送到 cmd task 的 nuc 队列
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ----------------------------------------------------------------- */
|
/* Includes ----------------------------------------------------------------- */
|
||||||
@ -13,9 +15,10 @@
|
|||||||
#include "module/aimbot.h"
|
#include "module/aimbot.h"
|
||||||
#include "module/config.h"
|
#include "module/config.h"
|
||||||
#include "module/vision_bridge.h"
|
#include "module/vision_bridge.h"
|
||||||
#include "component/ahrs/ahrs.h"
|
|
||||||
#include "module/gimbal.h"
|
#include "module/gimbal.h"
|
||||||
|
#include "module/shoot.h"
|
||||||
#include "device/referee_proto_types.h"
|
#include "device/referee_proto_types.h"
|
||||||
|
#include <string.h>
|
||||||
/* USER INCLUDE END */
|
/* USER INCLUDE END */
|
||||||
|
|
||||||
/* Private typedef ---------------------------------------------------------- */
|
/* Private typedef ---------------------------------------------------------- */
|
||||||
@ -24,12 +27,12 @@
|
|||||||
/* Private variables -------------------------------------------------------- */
|
/* Private variables -------------------------------------------------------- */
|
||||||
/* USER STRUCT BEGIN */
|
/* USER STRUCT BEGIN */
|
||||||
static Aimbot_Param_t aimbot_can; /* CAN 通信参数(从 config 拷贝) */
|
static Aimbot_Param_t aimbot_can; /* CAN 通信参数(从 config 拷贝) */
|
||||||
static Aimbot_FeedbackData_t aimbot_fb; /* 打包好的反馈数据 */
|
static Aimbot_FeedbackData_t lower_board_fb; /* 打包好发给上层板的数据 */
|
||||||
static Aimbot_AIResult_t aimbot_cmd; /* 从 CAN 解析到的 AI 指令 */
|
static Aimbot_AIResult_t ai_cmd_from_can; /* 上层板下发并传到底板的指令 */
|
||||||
static Gimbal_Feedback_t ai_gimbal_fb; /* 来自云台任务的反馈 */
|
|
||||||
static AHRS_Quaternion_t ai_imu_quat; /* 来自姿态估计任务的四元数 */
|
|
||||||
static Referee_ForAI_t ai_ref; /* 裁判系统转发给 AI 的数据 */
|
|
||||||
static AI_cmd_t ai_cmd_for_nuc; /* 转换后发往 cmd.nuc 的指令 */
|
static AI_cmd_t ai_cmd_for_nuc; /* 转换后发往 cmd.nuc 的指令 */
|
||||||
|
|
||||||
|
static Referee_ForAI_t ai_ref; /* 裁判系统转发给 AI 的数据 */
|
||||||
|
static Shoot_AI_t raw_shoot; /* 发射机构反馈 */
|
||||||
/* USER STRUCT END */
|
/* USER STRUCT END */
|
||||||
|
|
||||||
/* Private function --------------------------------------------------------- */
|
/* Private function --------------------------------------------------------- */
|
||||||
@ -52,33 +55,35 @@ void Task_ai(void *argument) {
|
|||||||
tick += delay_tick; /* 计算下一个唤醒时刻 */
|
tick += delay_tick; /* 计算下一个唤醒时刻 */
|
||||||
/* USER CODE BEGIN */
|
/* USER CODE BEGIN */
|
||||||
|
|
||||||
/* 读取裁判系统状态(非阻塞) */
|
/* 1. 读取裁判系统数据(获知机器人系统状态/弹速等) */
|
||||||
osMessageQueueGet(task_runtime.msgq.ai.ref, &ai_ref, NULL, 0);
|
osMessageQueueGet(task_runtime.msgq.ai.ref, &ai_ref, NULL, 0);
|
||||||
|
|
||||||
/* 读取云台反馈数据(非阻塞) */
|
/* 2. 读取发射机构反馈数据(非阻塞),以获取弹速、弹数等信息
|
||||||
osMessageQueueGet(task_runtime.msgq.ai.rawdata_FromGimbal, &ai_gimbal_fb, NULL, 0);
|
todo: 检查是否有单独发弹速消息队列
|
||||||
|
*/
|
||||||
|
osMessageQueueGet(task_runtime.msgq.ai.rawdata_FromShoot, &raw_shoot, NULL, 0);
|
||||||
|
|
||||||
/* 读取 IMU 四元数(非阻塞) */
|
/* 3. 打包当前底层板的数据(弹速、弹数、模式),通过CAN发送给上层板
|
||||||
osMessageQueueGet(task_runtime.msgq.ai.rawdata_FromIMU, &ai_imu_quat, NULL, 0);
|
由于现在只能拿到一部分,预留测试值,实车时接入射击模块返回的信息
|
||||||
|
*/
|
||||||
|
// TODO: 使用实际读取到的 bullet_speed 和 bullet_count
|
||||||
|
float current_bullet_speed = raw_shoot.bullet_speed;
|
||||||
|
uint16_t current_bullet_count = raw_shoot.num_shooted;
|
||||||
|
uint8_t current_mode = 1;
|
||||||
|
|
||||||
/* 打包反馈并通过 CAN 发给上层板(6 帧)
|
Aimbot_PackFeedback(&lower_board_fb, current_bullet_speed, current_bullet_count, current_mode);
|
||||||
* bullet_speed / bullet_count 暂无独立队列,置零;
|
Aimbot_SendFeedbackOnCAN(&aimbot_can, &lower_board_fb);
|
||||||
* 如有裁判系统弹速信息可在此处填入。 */
|
|
||||||
Aimbot_PackFeedback(&aimbot_fb, &ai_gimbal_fb, &ai_imu_quat,
|
|
||||||
0.0f, 0u,
|
|
||||||
(uint8_t)(ai_ref.ref_status == REF_STATUS_RUNNING ? 1u : 0u));
|
|
||||||
Aimbot_SendFeedbackOnCAN(&aimbot_can, &aimbot_fb);
|
|
||||||
|
|
||||||
/* 解析上层板发来的 AI 指令(非阻塞) */
|
/* 4. 解析上层板发来的 AI 指令(非阻塞提取) */
|
||||||
if (Aimbot_ParseCmdFromCAN(&aimbot_can, &aimbot_cmd) == DEVICE_OK) {
|
if (Aimbot_ParseCmdFromCAN(&aimbot_can, &ai_cmd_from_can) == DEVICE_OK) {
|
||||||
/* 将 Aimbot_AIResult_t 转换为 AI_cmd_t 并推送到 cmd.nuc 队列 */
|
/* 将 Aimbot_AIResult_t 转换为 AI_cmd_t 并推送到 cmd.nuc 队列 */
|
||||||
ai_cmd_for_nuc.mode = aimbot_cmd.mode;
|
ai_cmd_for_nuc.mode = ai_cmd_from_can.mode;
|
||||||
ai_cmd_for_nuc.gimbal.setpoint.yaw = aimbot_cmd.gimbal_t.setpoint.yaw;
|
ai_cmd_for_nuc.gimbal.setpoint.yaw = ai_cmd_from_can.gimbal_t.setpoint.yaw;
|
||||||
ai_cmd_for_nuc.gimbal.setpoint.pit = aimbot_cmd.gimbal_t.setpoint.pit;
|
ai_cmd_for_nuc.gimbal.setpoint.pit = ai_cmd_from_can.gimbal_t.setpoint.pit;
|
||||||
ai_cmd_for_nuc.gimbal.vel.yaw = aimbot_cmd.gimbal_t.vel.yaw;
|
ai_cmd_for_nuc.gimbal.vel.yaw = ai_cmd_from_can.gimbal_t.vel.yaw;
|
||||||
ai_cmd_for_nuc.gimbal.vel.pit = aimbot_cmd.gimbal_t.vel.pit;
|
ai_cmd_for_nuc.gimbal.vel.pit = ai_cmd_from_can.gimbal_t.vel.pit;
|
||||||
ai_cmd_for_nuc.gimbal.accl.yaw = aimbot_cmd.gimbal_t.accl.yaw;
|
ai_cmd_for_nuc.gimbal.accl.yaw = ai_cmd_from_can.gimbal_t.accl.yaw;
|
||||||
ai_cmd_for_nuc.gimbal.accl.pit = aimbot_cmd.gimbal_t.accl.pit;
|
ai_cmd_for_nuc.gimbal.accl.pit = ai_cmd_from_can.gimbal_t.accl.pit;
|
||||||
|
|
||||||
osMessageQueueReset(task_runtime.msgq.cmd.nuc);
|
osMessageQueueReset(task_runtime.msgq.cmd.nuc);
|
||||||
osMessageQueuePut(task_runtime.msgq.cmd.nuc, &ai_cmd_for_nuc, 0, 0);
|
osMessageQueuePut(task_runtime.msgq.cmd.nuc, &ai_cmd_for_nuc, 0, 0);
|
||||||
|
|||||||
@ -66,14 +66,14 @@ void Task_ctrl_chassis(void *argument) {
|
|||||||
: 500.0f;
|
: 500.0f;
|
||||||
Chassis_Power_Control(&chassis, power_limit);
|
Chassis_Power_Control(&chassis, power_limit);
|
||||||
|
|
||||||
Chassis_Output(&chassis);
|
// Chassis_Output(&chassis);
|
||||||
|
|
||||||
|
|
||||||
track.middle_val.seata=chassis.feedback.encoder_gimbalYawMotor-chassis.mech_zero;
|
track.middle_val.seata=chassis.feedback.encoder_gimbalYawMotor-chassis.mech_zero;
|
||||||
Track_UpdateFeedback(&track);
|
Track_UpdateFeedback(&track);
|
||||||
Track_Control(&track, &track_cmd );
|
Track_Control(&track, &track_cmd );
|
||||||
// Track_AutoControl(&track,&chassis);
|
// Track_AutoControl(&track,&chassis);
|
||||||
Track_Output(&track);
|
// Track_Output(&track);
|
||||||
|
|
||||||
/* USER CODE END */
|
/* USER CODE END */
|
||||||
osDelayUntil(tick); /* 运行结束,等待下一次唤醒 */
|
osDelayUntil(tick); /* 运行结束,等待下一次唤醒 */
|
||||||
|
|||||||
@ -4,6 +4,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/* Includes ----------------------------------------------------------------- */
|
/* Includes ----------------------------------------------------------------- */
|
||||||
|
#include "cmsis_os2.h"
|
||||||
#include "task/user_task.h"
|
#include "task/user_task.h"
|
||||||
/* USER INCLUDE BEGIN */
|
/* USER INCLUDE BEGIN */
|
||||||
#include "module/shoot.h"
|
#include "module/shoot.h"
|
||||||
@ -19,6 +20,7 @@
|
|||||||
Shoot_t shoot;
|
Shoot_t shoot;
|
||||||
Shoot_CMD_t shoot_cmd;
|
Shoot_CMD_t shoot_cmd;
|
||||||
Referee_ForShoot_t shoot_ref; /* 裁判系统发射数据 */
|
Referee_ForShoot_t shoot_ref; /* 裁判系统发射数据 */
|
||||||
|
Shoot_AI_t shoot_forai;
|
||||||
/* USER STRUCT END */
|
/* USER STRUCT END */
|
||||||
|
|
||||||
/* Private function --------------------------------------------------------- */
|
/* Private function --------------------------------------------------------- */
|
||||||
@ -43,6 +45,10 @@ void Task_ctrl_shoot(void *argument) {
|
|||||||
osMessageQueueGet(task_runtime.msgq.shoot.cmd, &shoot_cmd, NULL, 0);
|
osMessageQueueGet(task_runtime.msgq.shoot.cmd, &shoot_cmd, NULL, 0);
|
||||||
osMessageQueueGet(task_runtime.msgq.shoot.ref, &shoot_ref, NULL, 0);
|
osMessageQueueGet(task_runtime.msgq.shoot.ref, &shoot_ref, NULL, 0);
|
||||||
|
|
||||||
|
Shoot_DumpAI(&shoot, &shoot_forai);
|
||||||
|
osMessageQueuePut(task_runtime.msgq.ai.rawdata_FromShoot, &shoot_forai, 0, 0);
|
||||||
|
|
||||||
|
|
||||||
/* 消费裁判系统发射数据:在线时更新热量控制参数 */
|
/* 消费裁判系统发射数据:在线时更新热量控制参数 */
|
||||||
if (shoot_ref.ref_status == REF_STATUS_RUNNING) {
|
if (shoot_ref.ref_status == REF_STATUS_RUNNING) {
|
||||||
shoot.heatcontrol.Hmax = (float)shoot_ref.robot_status.shooter_barrel_heat_limit;
|
shoot.heatcontrol.Hmax = (float)shoot_ref.robot_status.shooter_barrel_heat_limit;
|
||||||
|
|||||||
@ -49,7 +49,7 @@ void Task_Init(void *argument) {
|
|||||||
task_runtime.thread.cmd = osThreadNew(Task_cmd, NULL, &attr_cmd);
|
task_runtime.thread.cmd = osThreadNew(Task_cmd, NULL, &attr_cmd);
|
||||||
task_runtime.thread.supercap = osThreadNew(Task_supercap, NULL, &attr_supercap);
|
task_runtime.thread.supercap = osThreadNew(Task_supercap, NULL, &attr_supercap);
|
||||||
task_runtime.thread.ai = osThreadNew(Task_ai, NULL, &attr_ai);
|
task_runtime.thread.ai = osThreadNew(Task_ai, NULL, &attr_ai);
|
||||||
// task_runtime.thread.referee = osThreadNew(Task_referee, NULL, &attr_referee);
|
task_runtime.thread.referee = osThreadNew(Task_referee, NULL, &attr_referee);
|
||||||
|
|
||||||
// 创建消息队列
|
// 创建消息队列
|
||||||
/* USER MESSAGE BEGIN */
|
/* USER MESSAGE BEGIN */
|
||||||
|
|||||||
@ -1,29 +1,28 @@
|
|||||||
|
|
||||||
|
|
||||||
OpenDocument="ctrl_gimbal.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_gimbal.c", Line=30
|
OpenDocument="referee_proto_types.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee_proto_types.h", Line=15
|
||||||
OpenDocument="startup_stm32h723xx.s", FilePath="D:/CUBEMX/hero/god-yuan-hero/startup_stm32h723xx.s", Line=51
|
OpenDocument="ctrl_gimbal.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_gimbal.c", Line=0
|
||||||
|
OpenDocument="startup_stm32h723xx.s", FilePath="D:/CUBEMX/hero/god-yuan-hero/startup_stm32h723xx.s", Line=48
|
||||||
OpenDocument="shoot.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/shoot.c", Line=33
|
OpenDocument="shoot.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/shoot.c", Line=33
|
||||||
OpenDocument="ref_main.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ref_main.c", Line=12
|
OpenDocument="ref_main.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ref_main.c", Line=12
|
||||||
OpenDocument="memcpy.c", FilePath="/build/gnu-tools-for-stm32_13.3.rel1.20250523-0900/src/newlib/newlib/libc/string/memcpy.c", Line=0
|
|
||||||
OpenDocument="referee.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee.h", Line=0
|
OpenDocument="referee.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee.h", Line=0
|
||||||
OpenDocument="referee.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/referee.c", Line=0
|
OpenDocument="uart.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/uart.c", Line=111
|
||||||
OpenDocument="uart.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/uart.c", Line=119
|
|
||||||
OpenDocument="supercap.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/supercap.c", Line=0
|
OpenDocument="supercap.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/supercap.c", Line=0
|
||||||
OpenDocument="stm32h7xx_it.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/stm32h7xx_it.c", Line=351
|
OpenDocument="stm32h7xx_it.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/stm32h7xx_it.c", Line=351
|
||||||
OpenDocument="cmsis_os2.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c", Line=515
|
OpenDocument="cmsis_os2.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Middlewares/Third_Party/FreeRTOS/Source/CMSIS_RTOS_V2/cmsis_os2.c", Line=515
|
||||||
OpenDocument="config.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/config.c", Line=466
|
OpenDocument="config.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/config.c", Line=455
|
||||||
OpenDocument="ctrl_shoot.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_shoot.c", Line=0
|
OpenDocument="ctrl_shoot.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_shoot.c", Line=0
|
||||||
OpenDocument="referee.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee.c", Line=21
|
OpenDocument="referee.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee.c", Line=21
|
||||||
OpenDocument="main.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/main.c", Line=60
|
OpenDocument="cmd.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/cmd.c", Line=51
|
||||||
OpenDocument="stm32h7xx_hal_fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_fdcan.c", Line=5367
|
OpenDocument="stm32h7xx_hal_fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_fdcan.c", Line=5367
|
||||||
OpenDocument="track.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/track.c", Line=87
|
OpenDocument="track.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/track.c", Line=87
|
||||||
OpenDocument="fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/fdcan.c", Line=240
|
OpenDocument="main.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/main.c", Line=60
|
||||||
OpenDocument="cmsis_gcc.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/CMSIS/Include/cmsis_gcc.h", Line=1193
|
OpenDocument="cmsis_gcc.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/CMSIS/Include/cmsis_gcc.h", Line=1193
|
||||||
OpenDocument="referee_proto_types.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/referee_proto_types.h", Line=15
|
OpenDocument="cmd.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/cmd/cmd.c", Line=192
|
||||||
OpenDocument="cmd.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/cmd.c", Line=51
|
OpenDocument="fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/fdcan.c", Line=98
|
||||||
OpenDocument="cmd.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/cmd/cmd.c", Line=0
|
OpenDocument="cmd.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/cmd/cmd.h", Line=0
|
||||||
OpenDocument="vision_bridge.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/vision_bridge.c", Line=78
|
OpenDocument="vision_bridge.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/vision_bridge.c", Line=78
|
||||||
OpenDocument="ctrl_chassis.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_chassis.c", Line=44
|
OpenDocument="ctrl_chassis.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/ctrl_chassis.c", Line=36
|
||||||
OpenDocument="motor.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/motor.h", Line=20
|
OpenDocument="motor.h", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/motor.h", Line=20
|
||||||
OpenDocument="filter.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/component/filter/filter.c", Line=54
|
OpenDocument="filter.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/component/filter/filter.c", Line=54
|
||||||
OpenDocument="user_math.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/component/user_math.c", Line=45
|
OpenDocument="user_math.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/component/user_math.c", Line=45
|
||||||
@ -34,29 +33,29 @@ OpenDocument="motor_rm.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/device/mo
|
|||||||
OpenDocument="stm32h7xx_hal_uart_ex.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart_ex.c", Line=964
|
OpenDocument="stm32h7xx_hal_uart_ex.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Drivers/STM32H7xx_HAL_Driver/Src/stm32h7xx_hal_uart_ex.c", Line=964
|
||||||
OpenDocument="queue.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Middlewares/Third_Party/FreeRTOS/Source/queue.c", Line=1275
|
OpenDocument="queue.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Middlewares/Third_Party/FreeRTOS/Source/queue.c", Line=1275
|
||||||
OpenDocument="chassis.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/chassis.c", Line=213
|
OpenDocument="chassis.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/module/chassis.c", Line=213
|
||||||
OpenDocument="supercap.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/supercap.c", Line=27
|
OpenDocument="supercap.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/supercap.c", Line=18
|
||||||
OpenDocument="atti_esti.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/atti_esti.c", Line=121
|
OpenDocument="atti_esti.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/task/atti_esti.c", Line=121
|
||||||
OpenDocument="fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/fdcan.c", Line=0
|
OpenDocument="fdcan.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/Core/Src/fdcan.c", Line=0
|
||||||
OpenDocument="time.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/time.c", Line=17
|
OpenDocument="time.c", FilePath="D:/CUBEMX/hero/god-yuan-hero/User/bsp/time.c", Line=17
|
||||||
OpenToolbar="Debug", Floating=0, x=0, y=0
|
OpenToolbar="Debug", Floating=0, x=0, y=0
|
||||||
OpenWindow="Registers 1", DockArea=RIGHT, x=0, y=1, w=728, h=594, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, FilteredItems=[], RefreshRate=1
|
OpenWindow="Registers 1", DockArea=RIGHT, x=0, y=1, w=728, h=589, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, FilteredItems=[], RefreshRate=1
|
||||||
OpenWindow="Source Files", DockArea=LEFT, x=0, y=0, w=328, h=930, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
OpenWindow="Source Files", DockArea=LEFT, x=0, y=0, w=328, h=930, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
||||||
OpenWindow="Disassembly", DockArea=RIGHT, x=0, y=0, w=728, h=335, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
OpenWindow="Disassembly", DockArea=RIGHT, x=0, y=0, w=728, h=340, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
||||||
OpenWindow="Memory 1", DockArea=BOTTOM, x=0, y=0, w=239, h=544, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, EditorAddress=0xFFFF5088
|
OpenWindow="Memory 1", DockArea=BOTTOM, x=0, y=0, w=239, h=544, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, EditorAddress=0xFFFF5088
|
||||||
OpenWindow="Watched Data 1", DockArea=RIGHT, x=0, y=1, w=728, h=594, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
OpenWindow="Watched Data 1", DockArea=RIGHT, x=0, y=1, w=728, h=589, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
||||||
OpenWindow="Functions", DockArea=LEFT, x=0, y=0, w=328, h=930, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
OpenWindow="Functions", DockArea=LEFT, x=0, y=0, w=328, h=930, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
||||||
OpenWindow="Data Sampling", DockArea=BOTTOM, x=2, y=0, w=866, h=525, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, VisibleTab=0, UniformSampleSpacing=0
|
OpenWindow="Data Sampling", DockArea=BOTTOM, x=2, y=0, w=866, h=525, TabPos=0, TopOfStack=1, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0, VisibleTab=0, UniformSampleSpacing=0
|
||||||
OpenWindow="Timeline", DockArea=BOTTOM, x=1, y=0, w=1453, h=544, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=1, DataPaneShown=1, PowerPaneShown=0, CodePaneShown=0, PinCursor="Cursor Movable", TimePerDiv="5 s / Div", TimeStampFormat="Time", DataGraphDrawAsPoints=0, DataGraphLegendShown=1, DataGraphUniformSampleSpacing=0, DataGraphLegendPosition="21;187", DataGraphShowNamesAtCursor=0, PowerGraphDrawAsPoints=0, PowerGraphLegendShown=0, PowerGraphAvgFilterTime=Off, PowerGraphAvgFilterLen=Off, PowerGraphUniformSampleSpacing=0, PowerGraphLegendPosition="1157;-69", CodeGraphLegendShown=0, CodeGraphLegendPosition="1164;0"
|
OpenWindow="Timeline", DockArea=BOTTOM, x=1, y=0, w=1453, h=544, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=1, DataPaneShown=1, PowerPaneShown=0, CodePaneShown=0, PinCursor="Cursor Movable", TimePerDiv="5 s / Div", TimeStampFormat="Time", DataGraphDrawAsPoints=0, DataGraphLegendShown=1, DataGraphUniformSampleSpacing=0, DataGraphLegendPosition="21;187", DataGraphShowNamesAtCursor=0, PowerGraphDrawAsPoints=0, PowerGraphLegendShown=0, PowerGraphAvgFilterTime=Off, PowerGraphAvgFilterLen=Off, PowerGraphUniformSampleSpacing=0, PowerGraphLegendPosition="1157;-69", CodeGraphLegendShown=0, CodeGraphLegendPosition="1164;0"
|
||||||
OpenWindow="Console", DockArea=BOTTOM, x=2, y=0, w=866, h=525, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
OpenWindow="Console", DockArea=BOTTOM, x=2, y=0, w=866, h=525, TabPos=1, TopOfStack=0, FilterBarShown=0, TotalValueBarShown=0, ToolBarShown=0
|
||||||
SmartViewPlugin="", Page="", Toolbar="Hidden", Window="SmartView 1"
|
SmartViewPlugin="", Page="", Toolbar="Hidden", Window="SmartView 1"
|
||||||
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=[118;100;100;100;100;100;110;126;126]
|
|
||||||
TableHeader="Registers 1", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Description"], ColWidths=[120;144;464]
|
TableHeader="Registers 1", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Description"], ColWidths=[120;144;464]
|
||||||
TableHeader="Functions", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Address";"Size";"#Insts";"Source"], ColWidths=[1594;104;100;100;100]
|
TableHeader="Functions", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Address";"Size";"#Insts";"Source"], ColWidths=[1594;104;100;100;100]
|
||||||
TableHeader="Power Sampling", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time";"Ch 0"], ColWidths=[100;100;100]
|
TableHeader="Power Sampling", SortCol="None", SortOrder="ASCENDING", VisibleCols=["Index";"Time";"Ch 0"], ColWidths=[100;100;100]
|
||||||
TableHeader="RegisterSelectionDialog", SortCol="None", SortOrder="ASCENDING", VisibleCols=[], ColWidths=[]
|
TableHeader="RegisterSelectionDialog", SortCol="None", SortOrder="ASCENDING", VisibleCols=[], ColWidths=[]
|
||||||
TableHeader="Source Files", SortCol="File", SortOrder="ASCENDING", VisibleCols=["File";"Status";"Size";"#Insts";"Path"], ColWidths=[215;100;100;100;1022]
|
TableHeader="Source Files", SortCol="File", SortOrder="ASCENDING", VisibleCols=["File";"Status";"Size";"#Insts";"Path"], ColWidths=[215;100;100;100;1022]
|
||||||
TableHeader="Watched Data 1", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Value";"Location";"Refresh"], ColWidths=[298;229;145;100]
|
TableHeader="Watched Data 1", SortCol="Expression", SortOrder="ASCENDING", VisibleCols=["Expression";"Value";"Location";"Refresh"], ColWidths=[298;229;145;100]
|
||||||
|
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=[118;100;100;100;100;100;110;126;126]
|
||||||
TableHeader="TargetExceptionDialog", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Address";"Description"], ColWidths=[200;100;100;340]
|
TableHeader="TargetExceptionDialog", SortCol="Name", SortOrder="ASCENDING", VisibleCols=["Name";"Value";"Address";"Description"], ColWidths=[200;100;100;340]
|
||||||
WatchedExpression="cmd", RefreshRate=5, Window=Watched Data 1
|
WatchedExpression="cmd", RefreshRate=5, Window=Watched Data 1
|
||||||
WatchedExpression="bmi088", RefreshRate=5, Window=Watched Data 1
|
WatchedExpression="bmi088", RefreshRate=5, Window=Watched Data 1
|
||||||
@ -74,3 +73,4 @@ WatchedExpression="imu_to_can", RefreshRate=5, Window=Watched Data 1
|
|||||||
WatchedExpression="ref", RefreshRate=5, Window=Watched Data 1
|
WatchedExpression="ref", RefreshRate=5, Window=Watched Data 1
|
||||||
WatchedExpression="rxbuf", RefreshRate=5, Window=Watched Data 1
|
WatchedExpression="rxbuf", RefreshRate=5, Window=Watched Data 1
|
||||||
WatchedExpression="shoot_ref", RefreshRate=5, Window=Watched Data 1
|
WatchedExpression="shoot_ref", RefreshRate=5, Window=Watched Data 1
|
||||||
|
WatchedExpression="gimbal_cmd", RefreshRate=5, Window=Watched Data 1
|
||||||
Loading…
Reference in New Issue
Block a user