跳转至

UDP_30100_TrueSimRecv 模块文档

所属工具箱:RflySim Model

UDP_30100_TrueSimRecv 模块外观

简介

一句话描述:通过监听UDP 30101++2系列端口,接收并解析来自载具模型仿真的完整状态真值数据。

该模块属于RflySim Model接口库,是RflySim工具链中获取高精度仿真真值状态的核心通信模块,主要用于外部控制、算法验证等需要获取载具真实仿真状态的开发场景。它会根据配置的飞机ID监听对应的UDP端口,接收外部载具模型或仿真环境发来的封装数据包,解析输出包含位置、速度、姿态、加速度、角速度、GPS信息、执行器状态等在内的完整载具状态真值。

该模块通常和CopterSim、RflySim3D配合使用:当用户在Simulink中搭建自定义载具模型或外部控制算法时,本模块负责从TrueSim仿真环境接收载具的真实状态数据,解析后可直接供Simulink中的算法模块使用,完成闭环仿真流程,支持多机仿真场景下通过飞机ID区分不同载具的状态数据。

端口说明

输入端口(Inputs)

本模块无输入端口。

输出端口(Outputs)

端口名 数据类型 维度 说明
checksum double 1×1 数据校验码,有效值为123456789,用于标识数据是否有效
copterID double 1×1 输出数据对应的飞机ID序号
vehicleType double 1×1 载具样式ID,对应RflySim3D UE场景XML中的ClassID
reserv double 1×1 备用标志位,预留用于表示碰撞、大地图等功能标识
VelE double 1×3 北东地坐标系下的载具速度,单位:米/秒
AngEuler double 1×3 滚转、俯仰、偏航欧拉角,单位:弧度
AngQuatern double 1×4 姿态四元数向量,顺序为w x y z
MotorRPMS double 1×8 执行器状态,旋翼类载具对应电机转速,单位:转/分钟
AccB double 1×3 载具机体FRD坐标系下的加速度,单位:米/平方秒
RateB double 1×3 载具机体FRD坐标系下的角速度p/q/r,单位:弧度/秒
runnedTime double 1×1 仿真时间戳,仿真开始时刻为0,单位:秒
PosE double 1×3 北东地坐标系下的载具位置,单位:米,z轴向下为正
PosGPS double 1×3 载具GPS坐标,顺序为纬度(度)、经度(度)、高度(米),高度向上为正

参数配置

双击模块打开的 Mask 对话框中可配置以下参数:

参数名 类型 默认值 可选值/范围 说明
CopterID int 1 1~255 需要监听读取数据的目标载具ID
Sample Time (s) double 0.01 >0 模块采样时间,单位:秒

参数设置说明

CopterID

目标载具的ID编号,模块会自动根据ID监听对应UDP端口30101 + 2 * (CopterID - 1),仅读取匹配对应ID的仿真真值数据。

Sample Time (s)

模块读取UDP数据的采样间隔,需根据仿真步长和数据发送频率匹配设置,一般多旋翼仿真使用默认值0.01秒即可。

模块特性(Block Characteristics)

特性项
支持的数据类型 doublesingleint32
直接馈通(Direct Feedthrough)
采样时间 离散
代码生成支持

数据通信协议

本模块基于UDP协议通信,端口规则为:对指定ID的飞机,监听本地UDP端口号为 30101 + 2 * CopterID

接收的数据包格式为封装后的netDataShort结构体,具体定义:

typedef struct _netDataShort {
    uint32_t tg;          // 目标端口标识
    int len;              // 传输结构体总长度,固定为200字节
    char payload[192];    // 有效载荷,前152字节存放SOut2Simulator结构体数据,剩余40字节保留
}netDataShort;

有效载荷中SOut2Simulator仿真真值结构体格式:

字段 类型 数量 说明
checksum int 1 有效数据校验码,固定为123456789
copterID int 1 飞机ID序号
vehicleType int 1 载具样式ID,对应RflySim3D UE场景XML中的ClassID
reserv int 1 备用标志位,预留用于碰撞、大地图标识
VelE float 3 北东地坐标系速度,单位:m/s
AngEuler float 3 滚转/俯仰/偏航欧拉角,单位:rad
AngQuatern float 4 姿态四元数,顺序为w x y z
MotorRPMS float 8 执行器状态,旋翼类对应电机转速,单位:RPM
AccB float 3 机体FRD坐标系加速度,单位:m/s²
RateB float 3 机体FRD坐标系角速度pqr,单位:rad/s
runnedTime double 1 时间戳,仿真开始时刻为0,单位:s
PosE double 3 北东地坐标系位置,z向下为正,单位:m
PosGPS double 3 纬度/经度/高度,纬度经度单位为度,高度单位为米,高度向上为正

完整数据解码标识为4i 24f 7d,总数据长度为168字节。

相关模块

模块名 说明
UDP_30100_ExtCtrlSend 向外发送外部控制指令,对应UDP 30100端口系列
MAVLinkRecv 接收MAVLink协议格式的无人机状态数据
MAVLinkSend 发送MAVLink协议格式的控制指令数据

使用示例

相关使用示例请参考以下路径:

[RflySim安装路径]/RflySimAPIs/4.RflySimModel/0.ApiExps/3.ExtCtrlAPI/2.ExtCtrlAPI-UDP30100/Readme.pdf

请在上述路径中查看 Readme.pdf 获取完整的示例说明与操作步骤。

注意事项与常见问题

  • 初始化顺序:该模块依赖RflySim3D可视化引擎发送UDP真值数据,必须先启动RflySim3D仿真环境并完成载具模型初始化后,再启动Simulink仿真,否则会出现持续接收不到有效数据的情况。
  • CopterID匹配:模块根据配置的CopterID自动监听对应端口(30101 + 2 * (CopterID - 1)),CopterID必须与RflySim3D中发送仿真真值的目标载具ID一致,否则无法接收到对应载具的真值数据。
  • 坐标系与单位注意:输出真值中,PosE为北东地坐标系,Z轴向下为正;PosGPS纬度经度单位为度,高度单位为米且向上为正,使用输出数据时需要注意坐标系和单位的转换,避免逻辑错误。
  • 校验码校验:模块仅会解析校验码为123456789的数据包,若接收数据全为0,可检查发送端是否正确设置了校验码,确保数据有效性。
  • 采样时间匹配:模块的Sample Time (s)需要和发送端仿真真值的输出频率匹配,建议设置为和发送端一致,避免数据丢包或重复读取的问题。
  • 防火墙拦截:该模块通过本地UDP端口通信,若始终无法接收数据,需检查操作系统防火墙是否拦截了MATLAB/Simulink的UDP网络访问权限。

更新日志

  • v4.1.0 (2024-01-15): 初始版本发布,实现监听UDP 30101++2系列端口读取载具模型仿真真值功能,支持多载具ID配置与自定义采样时间设置。