175 lines
6.2 KiB
C
175 lines
6.2 KiB
C
|
||
#pragma once
|
||
|
||
#ifdef __cplusplus
|
||
extern "C" {
|
||
#endif
|
||
|
||
/* Includes ----------------------------------------------------------------- */
|
||
#include "component/user_math.h"
|
||
#include "module/gimbal.h"
|
||
#include "bsp/fdcan.h"
|
||
#include <stdint.h>
|
||
|
||
// 数据包协议定义(UART 通信使用 head[2]={'M', 'R'} 标识)
|
||
|
||
/* ============================ CAN 通信定义 ============================
|
||
* 通路:上位机 <--串口--> 上层板 <--CAN--> 下层板
|
||
*
|
||
* 注:上层板使用自己的IMU(atti_esti),下层板只需反馈电机和射击数据
|
||
*
|
||
* 下层板 → 上层板:反馈数据,单帧 8 字节
|
||
* 帧0 (fb_base_id+0): 弹速(4B) + 弹数(2B) + 模式(1B) + 保留(1B)
|
||
*
|
||
* 上层板 → 下层板:AI 指令,单帧 8 字节
|
||
* 帧 (cmd_id): mode(1B) + yaw(28bit) + pit(28bit),定点数精度 0.1µrad
|
||
* ====================================================================== */
|
||
#define AIMBOT_FB_FRAME_NUM 1u /* 反馈数据帧总数(仅下层三字段) */
|
||
#define AIMBOT_CAN_DLC 8u /* CAN 帧数据长度 */
|
||
#define AIMBOT_ANGLE_SCALE 10000000.0f /* 指令角度定点数比例(0.1µrad/LSB) */
|
||
|
||
/* CAN 通信参数结构体 */
|
||
typedef struct {
|
||
BSP_FDCAN_t can; /* 使用的 CAN 总线实例 */
|
||
uint32_t cmd_id; /* 上层板→下层板 AI 指令帧 CAN ID */
|
||
uint32_t fb_base_id; /* 下层板→上层板 反馈数据起始 CAN ID */
|
||
} Aimbot_Param_t;
|
||
|
||
/* CAN 反馈数据结构体(下层板打包后经 CAN 发给上层板的内容)
|
||
* 注:下层板只反馈 bullet_speed / bullet_count / mode */
|
||
typedef struct {
|
||
uint8_t mode; /* 下层板当前工作模式 */
|
||
float bullet_speed; /* 弹速(m/s) */
|
||
uint16_t bullet_count; /* 子弹累计发射次数 */
|
||
} Aimbot_FeedbackData_t;
|
||
|
||
/*-----------------------------to上位机---------------------------------*/
|
||
typedef struct __attribute__((packed))
|
||
{
|
||
uint8_t head[2]; // 数据包头: {'M', 'R'}
|
||
uint8_t mode; // 0: 空闲, 1: 自瞄, 2: 小符, 3: 大符
|
||
float q[4]; // 四元数 wxyz 顺序
|
||
float yaw; // 偏航角
|
||
float yaw_vel; // 偏航角速度
|
||
float pitch; // 俯仰角
|
||
float pitch_vel; // 俯仰角速度
|
||
float bullet_speed; // 弹速
|
||
uint16_t bullet_count; // 子弹累计发送次数
|
||
uint16_t crc16; // CRC16 校验
|
||
} Aimbot_MCU_t;
|
||
|
||
// 裁判系统数据结构
|
||
typedef struct __attribute__((packed))
|
||
{
|
||
uint16_t remain_hp; // 剩余血量
|
||
uint8_t game_progress : 4; // 比赛进度
|
||
uint16_t stage_remain_time; // 比赛剩余时间
|
||
} Aimbot_RefereeData_t;
|
||
|
||
typedef struct __attribute__((packed))
|
||
{
|
||
uint8_t id; // 数据包 ID: 0xA8
|
||
Aimbot_RefereeData_t data;
|
||
uint16_t crc16;
|
||
} Aimbot_Referee_t;
|
||
|
||
/*------------------------------------上位机back-------------------------------------*/
|
||
typedef struct __attribute__((packed))
|
||
{
|
||
uint8_t head[2]; // 数据包头: {'M', 'R'}
|
||
uint8_t mode; // 0: 不控制, 1: 控制云台但不开火,2: 控制云台且开火
|
||
float yaw; // 目标偏航角
|
||
float yaw_vel; // 偏航角速度
|
||
float yaw_acc; // 偏航角加速度
|
||
float pitch; // 目标俯仰角
|
||
float pitch_vel; // 俯仰角速度
|
||
float pitch_acc; // 俯仰角加速度
|
||
uint16_t crc16; // CRC16 校验
|
||
} Aimbot_AI_t;
|
||
|
||
typedef struct __attribute__((packed)) {
|
||
uint8_t mode; // 0: 不控制, 1: 控制云台但不开火, 2: 控制云台且开火
|
||
struct{
|
||
// Gimbal_CMD_t g_cmd;
|
||
struct{
|
||
float yaw; // 目标偏航角
|
||
float pit; // 目标俯仰角
|
||
}setpoint;
|
||
|
||
struct{
|
||
float pit; // 俯仰角加速度
|
||
float yaw; // 偏航角加速度
|
||
}accl;
|
||
struct{
|
||
float pit; // 俯仰角速度
|
||
float yaw; // 偏航角速度
|
||
}vel;
|
||
}gimbal_t;
|
||
|
||
struct{
|
||
float Vx; // X 方向速度
|
||
float Vy; // Y 方向速度
|
||
float Vw; // Z 方向角速度
|
||
}chassis_t;
|
||
|
||
uint8_t reserved; // 预留字段
|
||
} Aimbot_AIResult_t; // 解析后的AI控制指令
|
||
|
||
/* ---------- UART 通信接口(上层板与上位机 PC 间) ---------- */
|
||
int8_t Aimbot_MCUPack(Aimbot_MCU_t *mcu, const Gimbal_Feedback_t *gimbal_fb,
|
||
const AHRS_Quaternion_t *quat,
|
||
float bullet_speed, uint16_t bullet_count, uint8_t mode);
|
||
int8_t Aimbot_MCUStartSend(Aimbot_MCU_t *mcu);
|
||
int8_t Aimbot_AIGetResult(Aimbot_AI_t *ai, Aimbot_AIResult_t *result);
|
||
int8_t Aimbot_AIStartRecv(Aimbot_AI_t *ai);
|
||
|
||
/* ---------- CAN 通信接口(下层板与上层板间) ---------- */
|
||
|
||
/**
|
||
* @brief 初始化 Aimbot CAN 通信,注册所有收发 CAN ID 队列
|
||
* @param param CAN 通信参数
|
||
* @return DEVICE_OK / DEVICE_ERR_NULL
|
||
*/
|
||
int8_t Aimbot_Init(Aimbot_Param_t *param);
|
||
|
||
/**
|
||
* @brief 【下层板】打包反馈结构体
|
||
* @param fb 输出:反馈数据
|
||
* @param bullet_speed 弹速(m/s)
|
||
* @param bullet_count 已发射子弹数
|
||
* @param mode 当前工作模式
|
||
*/
|
||
int8_t Aimbot_PackFeedback(Aimbot_FeedbackData_t *fb,
|
||
float bullet_speed, uint16_t bullet_count,
|
||
uint8_t mode);
|
||
|
||
/**
|
||
* @brief 【下层板】将反馈数据经 CAN 发送给上层板(1 帧)
|
||
*/
|
||
void Aimbot_SendFeedbackOnCAN(const Aimbot_Param_t *param,
|
||
const Aimbot_FeedbackData_t *fb);
|
||
|
||
/**
|
||
* @brief 【下层板】从 CAN 解析上层板发来的 AI 指令
|
||
* @return DEVICE_OK 表示成功取到新数据;DEVICE_ERR 表示队列暂无数据
|
||
*/
|
||
int8_t Aimbot_ParseCmdFromCAN(const Aimbot_Param_t *param,
|
||
Aimbot_AIResult_t *result);
|
||
|
||
/**
|
||
* @brief 【上层板】通过 CAN 将 AI 指令发送给下层板(单帧 8 字节)
|
||
*/
|
||
void Aimbot_SendCmdOnCAN(const Aimbot_Param_t *param,
|
||
const Aimbot_AIResult_t *cmd);
|
||
|
||
/**
|
||
* @brief 【上层板】从 CAN 解析下层板发来的反馈数据(逐帧读取,非阻塞)
|
||
* @return DEVICE_OK(部分或全部帧已更新均返回 OK)
|
||
*/
|
||
int8_t Aimbot_ParseFeedbackFromCAN(const Aimbot_Param_t *param,
|
||
Aimbot_FeedbackData_t *fb);
|
||
|
||
#ifdef __cplusplus
|
||
}
|
||
#endif
|