裁判系统串口
Referee 类实现了 RoboMaster 裁判系统串口协议的完整解析,支持多个协议版本,包含自动分包、CRC 校验、丢包率统计等功能。
支持的协议版本
librm 支持以下裁判系统串口协议版本:
| 版本 | 枚举值 | 发布日期 |
|---|---|---|
| V1.6.4 | RefereeRevision::kV164 | 2024-07-15 |
| V1.7.0 | RefereeRevision::kV170 | 2024-12-25 |
| 新通信协议 V1.1.0 | RefereeRevision::kNewV110 | 2025-12-17 |
基本使用
#include <librm.hpp>
const unsigned char mock_data[10] = {0xa5, 0x05, 0x00, 0x00, 0x00,
0x01, 0x00, 0x00, 0x00, 0x00};
int main() {
// 指定协议版本创建 Referee 对象
rm::device::Referee<rm::device::RefereeRevision::kV170> ref;
// 把接收到的数据一个字节一个字节地扔进Referee对象即可
for (const auto &data : mock_data) {
ref << data;
}
// 通过Referee对象的data()方法获取数据
ref.data().custom_robot_data;
ref.data().event_data;
ref.data().game_robot_HP.blue_3_robot_HP;
// ...
return 0;
}
与串口配合使用
STM32 HAL 库示例
#include "usart.h"
#include "cmsis_os.h"
#include <librm.hpp>
rm::device::Referee<rm::device::RefereeRevision::kV170> referee;
uint8_t rx_buffer[128];
// 使用 DMA 空闲中断接收
extern "C" void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size) {
if (huart == &huart6) {
// 将接收到的数据逐字节送入 Referee 对象
for (uint16_t i = 0; i < Size; i++) {
referee << rx_buffer[i];
}
// 重新启动接收
HAL_UARTEx_ReceiveToIdle_DMA(&huart6, rx_buffer, sizeof(rx_buffer));
}
}
extern "C" void RefereeTask(const void *pv_arg) {
// 启动 DMA 接收
HAL_UARTEx_ReceiveToIdle_DMA(&huart6, rx_buffer, sizeof(rx_buffer));
for (;;) {
// 读取底盘功率限制
uint16_t power_limit = referee.data().robot_status.chassis_power_limit;
// 读取枪口热量
uint16_t heat = referee.data().power_heat_data.shooter_17mm_1_barrel_heat;
// 读取缓冲能量
uint16_t buffer = referee.data().power_heat_data.buffer_energy;
osDelay(10);
}
}
回调函数
可以使用 AttachCallback 方法注册回调函数,在接收到完整数据包并通过 CRC 校验后自动调用。回调函数会接收到 cmd_id 和包序列号 seq 作为参数。
#include <librm.hpp>
int main() {
rm::device::Referee<rm::device::RefereeRevision::kV170> ref;
// 注册回调函数
ref.AttachCallback([&ref](u16 cmd_id, u8 seq) {
// 根据cmd_id处理不同类型的数据
if (cmd_id == 0x0001) {
// 处理比赛状态数据
auto game_status = ref.data().game_status;
// ...
} else if (cmd_id == 0x0003) {
// 处理机器人血量数据
auto robot_hp = ref.data().game_robot_HP;
// ...
}
});
// 可以注册多个回调函数,它们会按注册顺序依次执行
ref.AttachCallback([](u16 cmd_id, u8 seq) {
printf("Received packet: cmd_id=0x%04x, seq=%d\n", cmd_id, seq);
});
// 接收数据
// ref << uart_data;
return 0;
}
丢包率监控
Referee 类会自动统计丢包率,可用于监控通信质量:
rm::device::Referee<rm::device::RefereeRevision::kV170> ref;
// 获取近 10 轮平均丢包率(百分比)
float loss = ref.loss_rate();
if (loss > 10.0f) {
// 丢包率过高,可能需要检查串口连接
printf("Warning: High packet loss rate: %.1f%%\n", loss);
}
数据结构参考(以V1.7.0为例)
命令码定义
使用 RefereeCmdId 可以获取各数据包的命令码:
using CmdId = rm::device::RefereeCmdId<rm::device::RefereeRevision::kV170>;
// 比赛状态: 0x0001
CmdId::kGameStatus;
// 比赛结果: 0x0002
CmdId::kGameResult;
// 机器人血量: 0x0003
CmdId::kGameRobotHp;
// 场地事件: 0x0101
CmdId::kEventData;
// 裁判警告: 0x0104
CmdId::kRefereeWarning;
// 飞镖信息: 0x0105
CmdId::kDartInformation;
// 机器人状态: 0x0201
CmdId::kRobotStatus;
// 功率热量: 0x0202
CmdId::kPowerHeatData;
// 机器人位置: 0x0203
CmdId::kRobotPos;
// 增益: 0x0204
CmdId::kBuff;
// 伤害: 0x0206
CmdId::kHurtData;
// 射击: 0x0207
CmdId::kShootData;
// 弹丸余量: 0x0208
CmdId::kProjectileAllowance;
// RFID 状态: 0x0209
CmdId::kRfidStatus;
// 飞镖客户端: 0x020A
CmdId::kDartClientCmd;
// 地面机器人位置: 0x020B
CmdId::kGroundRobotPosition;
// 雷达标记: 0x020C
CmdId::kRadarMarkData;
// 哨兵信息: 0x020D
CmdId::kSentryInfo;
// 雷达信息: 0x020E
CmdId::kRadarInfo;
// 自定义机器人数据(图传链路): 0x0302
CmdId::kCustomRobotData;
// 小地图命令: 0x0303
CmdId::kMapCommand;
// 图传遥控(图传链路): 0x0304
CmdId::kRemoteControl;
常用数据字段
机器人状态 (robot_status)
auto& status = ref.data().robot_status;
status.robot_id; // 机器人 ID
status.robot_level; // 机器人等级
status.current_HP; // 当前血量
status.maximum_HP; // 最大血量
status.shooter_barrel_cooling_value; // 枪口冷却值
status.shooter_barrel_heat_limit; // 枪口热量上限
status.chassis_power_limit; // 底盘功率限制
status.power_management_gimbal_output; // 云台输出状态
status.power_management_chassis_output; // 底盘输出状态
status.power_management_shooter_output; // 发射机构输出状态
功率热量数据 (power_heat_data)
auto& power = ref.data().power_heat_data;
power.buffer_energy; // 缓冲能量
power.shooter_17mm_1_barrel_heat; // 17mm 1 号枪口热量
power.shooter_17mm_2_barrel_heat; // 17mm 2 号枪口热量
power.shooter_42mm_barrel_heat; // 42mm 枪口热量
射击数据 (shoot_data)
auto& shoot = ref.data().shoot_data;
shoot.bullet_type; // 弹丸类型(1: 17mm, 2: 42mm)
shoot.shooter_number; // 发射机构 ID
shoot.launching_frequency; // 发射频率
shoot.initial_speed; // 弹丸初速度
伤害数据 (hurt_data)
auto& hurt = ref.data().hurt_data;
hurt.armor_id; // 受击装甲 ID(0-4)
hurt.HP_deduction_reason; // 扣血原因
机器人位置 (robot_pos)
auto& pos = ref.data().robot_pos;
pos.x; // x 坐标
pos.y; // y 坐标
pos.angle; // 朝向角度
图传遥控 (remote_control)
图传链路下发的键鼠数据:
auto& rc = ref.data().remote_control;
rc.mouse_x; // 鼠标 X 轴移动速度
rc.mouse_y; // 鼠标 Y 轴移动速度
rc.mouse_z; // 鼠标滚轮
rc.left_button_down; // 左键状态
rc.right_button_down; // 右键状态
rc.keyboard_value; // 键盘按键位掩码
// 键盘按键判断
if (rc.keyboard_value & rc.kW) {
// W 键按下
}
if (rc.keyboard_value & rc.kShift) {
// Shift 键按下
}
键盘按键枚举:
| 按键 | 值 |
|---|---|
| W | 0x0001 |
| S | 0x0002 |
| A | 0x0004 |
| D | 0x0008 |
| Shift | 0x0010 |
| Ctrl | 0x0020 |
| Q | 0x0040 |
| E | 0x0080 |
| R | 0x0100 |
| F | 0x0200 |
| G | 0x0400 |
| Z | 0x0800 |
| X | 0x1000 |
| C | 0x2000 |
| V | 0x4000 |
| B | 0x8000 |
API 参考
构造函数
template <RefereeRevision revision>
Referee();
模板参数 revision 指定协议版本。
主要方法
| 方法 | 说明 |
|---|---|
void operator<<(u8 data) | 输入一个字节的数据 |
void AttachCallback(const RxCallback& callback) | 注册数据接收回调函数 |
const RefereeProtocol<revision>& data() const | 获取解析后的数据 |
f32 loss_rate() const | 获取近 10 轮平均丢包率(百分比) |
回调函数类型
using RxCallback = std::function<void(u16 cmd_id, u8 seq)>;
cmd_id: 接收到的数据包命令码seq: 数据包序列号
注意事项
tip
Referee类设计为与硬件平台解耦,需要用户自行实现串口接收并调用operator<<- 回调函数会在数据包 CRC 校验通过后同步执行,注意不要在回调中执行耗时操作