跳转至

RflySim3D 多模态传感器 API 文档

本文档描述 RflySim 中所有 多模态传感器 的参数定义。


版本限制总览

版本 支持的 TypeID 传感器数量限制 目标飞机限制
免费版 (CurrentVersion < 6) 1, 2, 3, 4, 5, 8, 10, 20, 21, 22, 23, 30, 31 最多 3 个 (SeqID < 3) 仅 Copter#1 (TargetMountType=4 除外)
付费版 (CurrentVersion ≥ 6) 全部 18 种 无限制 无限制

付费版独占传感器: Type 6 (声音)、Type 7 (深度点云)、Type 9 (吊舱)、Type 40 (红外灰度)、Type 41 (红外伪彩色)。


通用参数说明 (VisionSensorReqNew)

字段 类型 说明
checksum uint16 数据校验位,固定为 12346
SeqID uint16 传感器实例序号 ID(唯一标识)
bitmask uint32 保留位掩码
TypeID uint16 传感器类型 ID(本文档核心)
TargetCopter uint16 绑定的目标飞机 ID(可动态变更)
TargetMountType uint16 安装模式(见下方详细说明)
DataWidth uint16 数据/图像宽度(像素 或 射线列数)
DataHeight uint16 数据/图像高度(像素 或 射线行数)
DataCheckFreq uint16 数据更新频率 (Hz),0 时默认 30Hz
SendProtocol[8] uint16[8] 传输协议参数(见下方详细说明)
CameraFOV float 相机视场角 (度),仅视觉类传感器有效
SensorPosXYZ[3] float[3] 传感器安装位置 (NED, 米)
EulerOrQuat float >0.5 使用四元数,≤0.5 使用欧拉角
SensorAngEuler[3] float[3] 传感器安装欧拉角 (Roll, Pitch, Yaw, 度)
SensorAngQuat[4] float[4] 传感器安装四元数 (w, x, y, z)
otherParams[16] float[16] 各传感器专用参数(见各类型说明)

传感器安装模式 (TargetMountType)

模式 说明
0 载具固连 传感器随载具整体运动(位置+姿态跟随)
1 载具底部固连 与模式 0 类似,但 Z 偏移减去载具中心高度
2 世界固定 传感器位置/姿态使用世界绝对坐标,不跟随任何载具
3 Yaw 独立 位置跟随载具,但 Yaw 姿态保持世界坐标系
4 传感器附加 附加到另一个传感器上,此时 TargetCopter 表示目标传感器的 SeqID

数据传输模式 (SendProtocol)

索引 字段 说明
[0] sendMode 传输模式: 0=共享内存, 1=UDP 无压缩, 2/3=UDP 视频流
[1-4] IP 地址 当 sendMode=1/2/3 时,指定目标 IP (四段)
[5] 端口号 当 sendMode=1/2/3 时,指定目标端口
[6] sendModeEx UDP 分片大小 (bytes)。有效范围 100–60000,默认 60000。控制每个 UDP 包的有效载荷大小
[7] 功能标志位 各类型含义不同(见各传感器说明)

注意: Type 5, 7, 10, 20–23, 30, 31 不支持 sendMode 2 和 3 (自动降级为 1)。


传感器类型详细参数

Type 1 — RGB 图像

可见光取图

项目 说明
用途 捕获彩色场景图像
获取原理 在传感器位置放置虚拟相机,渲染当前视角的全彩图像
输出格式 RGB 彩色图 (W×H×3 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Config.json 示例

{
    "VisionSensors": [{
        "SeqID": 0,              // 传感器序号,填0则自动递增
        "TypeID": 1,             // 传感器类型:1=RGB
        "TargetCopter": 1,       // 绑定飞机ID(免费版仅支持1号)
        "TargetMountType": 0,    // 安装模式:0=载具固连
        "DataWidth": 640,        // 图像宽度(像素)
        "DataHeight": 480,       // 图像高度(像素)
        "DataCheckFreq": 30,     // 数据更新频率(Hz)
        "SendProtocol": [0,0,0,0,0,0,0,0], // [0]=传输模式(0:共享内存,1:UDP), [1-4]=IP, [5]=端口, [6]=分片大小, [7]=功能位
        "CameraFOV": 90,         // 视场角(度)
        "EularOrQuat": 0,        // 0=欧拉角, >0.5=四元数
        "SensorPosXYZ": [0.3, 0, 0],     // 安装位置偏移(NED,米)
        "SensorAngQuat": [0,0,0,0],      // 四元数姿态 (w,x,y,z)
        "SensorAngEular": [0,0,0],       // 欧拉角姿态 (Roll,Pitch,Yaw,度)
        "otherParams": [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0]  // 专用参数(RGB无需设置)
    }]
}

Python 取图 Demo

以下为所有图像类传感器 (1, 2, 3, 4, 8, 40, 41) 通用的取图流程。后续传感器仅列出差异部分。

import VisionCaptureApi
import cv2, time, sys

vis = VisionCaptureApi.VisionCaptureApi()  # 可传入 RflySim3D 的 IP

# 1. 加载 Config.json
vis.jsonLoad()                  # 默认加载同目录下 Config.json

# 2. 向 RflySim3D 发送取图请求
if not vis.sendReqToUE4():
    sys.exit(0)

# 3. 开启取图线程
vis.startImgCap()

# 4. 循环读取图像
while True:
    time.sleep(1/30.0)
    for i in range(len(vis.hasData)):
        if vis.hasData[i]:
            cv2.imshow('Img'+str(i), vis.Img[i])  # vis.Img[i]: np.ndarray (H×W×3, uint8, BGR)
            cv2.waitKey(1)

# 实时更新传感器参数
vs = vis.VisSensor[0]
vs.CameraFOV = 60
vs.SensorPosXYZ = [0.3, 0, 0]
vis.sendUpdateUEImage(vs)

Python 输出: vis.Img[i]np.ndarray (H×W×3, uint8, BGR 彩色图)

ROS 数据

话题 消息类型 编码
/rflysim/sensor{SeqID}/img_rgb sensor_msgs/Image bgr8

ROS2 区分: ROS1 使用 rospy.Publisher;ROS2 使用 node.create_publisher + QoSProfile(depth=10, reliability=RELIABLE)。需设置 VisionCaptureApi.isEnableRosTrans = True 启用。

C++ ROS 订阅 Demo

ROS1:

#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui.hpp>

void imageCallback(const sensor_msgs::ImageConstPtr& msg) {
    cv::Mat img = cv_bridge::toCvShare(msg, "bgr8")->image;
    cv::imshow("RflySim RGB", img);
    cv::waitKey(1);
}

int main(int argc, char** argv) {
    ros::init(argc, argv, "rflysim_img_sub");
    ros::NodeHandle nh;
    // 话题名按实际 SeqID 修改,如 /rflysim/sensor0/img_rgb
    ros::Subscriber sub = nh.subscribe("/rflysim/sensor0/img_rgb", 1, imageCallback);
    ros::spin();
    return 0;
}

ROS2:

#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui.hpp>

class ImgSub : public rclcpp::Node {
public:
    ImgSub() : Node("rflysim_img_sub") {
        // ROS2 需指定 QoS,与 SDK 发布端保持一致
        auto qos = rclcpp::QoS(10)
            .reliability(rclcpp::ReliabilityPolicy::Reliable)
            .durability(rclcpp::DurabilityPolicy::TransientLocal);
        sub_ = create_subscription<sensor_msgs::msg::Image>(
            "/rflysim/sensor0/img_rgb", qos,
            [this](sensor_msgs::msg::Image::SharedPtr msg) {
                auto img = cv_bridge::toCvShare(msg, "bgr8")->image;
                cv::imshow("RflySim RGB", img);
                cv::waitKey(1);
            });
    }
private:
    rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr sub_;
};

int main(int argc, char** argv) {
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<ImgSub>());
    rclcpp::shutdown();
    return 0;
}

注意: ROS2 订阅端的 QoS 需与 SDK 发布端一致(Reliable + TransientLocal),否则无法收到消息。话题名中的 sensor0 按实际 SeqID 替换。

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\4.SendProtocolAPI


Type 2 — 深度图

深度图像

项目 说明
用途 获取场景中每个像素到相机的距离信息
获取原理 在传感器位置放置虚拟相机,采用浮点精度渲染场景深度
输出格式 16-bit 深度图 (W×H×2 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Python 输出: vis.Img[i]np.ndarray (H×W, uint16, 16-bit 深度值)。取图流程同 Type 1,Config.json 中 TypeID 改为 2 即可。

ROS: /rflysim/sensor{SeqID}/img_depth · sensor_msgs/Image · 编码 mono16

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\1.ImgSenorAPI\3.DepthCameraDemo


Type 3 — 灰度图

灰度图

项目 说明
用途 捕获单通道灰度场景图像
获取原理 在传感器位置放置虚拟相机,渲染彩色图像后转换为灰度
输出格式 单通道灰度 (W×H×1 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Python 输出: vis.Img[i]np.ndarray (H×W, uint8, 单通道灰度)。取图流程同 Type 1TypeID 改为 3

ROS: /rflysim/sensor{SeqID}/img_gray · sensor_msgs/Image · 编码 mono8

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\4.SendProtocolAPI


Type 4 — 分割图

分割图

项目 说明
用途 语义分割图像,场景中不同物体按其标注值分配不同颜色
获取原理 在传感器位置放置虚拟相机,根据每个物体预设的分割标注值 (CustomDepthStencilValue) 进行着色渲染
输出格式 RGB 彩色图 (W×H×3 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Python 输出: vis.Img[i]np.ndarray (H×W×3, uint8, BGR 分割图)。取图流程同 Type 1TypeID 改为 4

ROS: /rflysim/sensor{SeqID}/img_Segmentation · sensor_msgs/Image · 编码 bgr8

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\1.ImgSenorAPI\5.SegmentImageDemo


Type 5 — 测距传感器

项目 说明
用途 单射线距离测量 (前向)
获取原理 从传感器位置沿前向发射一条射线,检测与场景物体的碰撞并返回距离
DataCheckFreq 测距频率 (Hz)
共享内存大小 1 + 8 + 14×4 = 65 bytes

otherParams 定义:

索引 参数 说明
[0] maxRange 最大测距距离 (米)

输出数据包含: - Distance: 测量距离 (米),未命中返回 -1 - disCopterID: 命中目标的 CopterID (-1 为非飞机目标) - disData[0-2]: 发射点位置 (NED, 米) - disData[3-5]: 传感器姿态角 (Roll, Pitch, Yaw, 度) - disData[6-8]: 命中点位置 (NED, 米) - disData[9-11]: 命中目标中心位置 (NED, 米)

Python 输出: vis.DistanceSensorDistanceSensor 对象,含 .Distance(米), .CopterID, .RayStart[3], .AngEular[3], .ImpactPoint[3], .BoxOri[3]

测距传感器通常使用 TargetMountType=4 挂载到一个图像传感器上,共享位置和姿态。

Config.json 示例(挂载到 RGB 相机)

{
    "VisionSensors": [
        {
            "SeqID": 0,
            "TypeID": 1,              // 先创建 RGB 相机
            "TargetCopter": 1,
            "TargetMountType": 0,
            "DataWidth": 640,
            "DataHeight": 480,
            "DataCheckFreq": 30,
            "SendProtocol": [1,0,0,0,0,0,0,0],  // UDP 模式
            "CameraFOV": 90,
            "EularOrQuat": 0,
            "SensorPosXYZ": [0.3, 0, 0],
            "SensorAngQuat": [0,0,0,0],
            "SensorAngEular": [0,0,0],
            "otherParams": [0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0]
        },
        {
            "SeqID": 0,
            "TypeID": 5,              // 测距传感器挂载到上方 RGB
            "TargetCopter": 0,
            "TargetMountType": 4,     // MountType=4 挂载到 SeqID=0 的传感器
            "DataWidth": 640,
            "DataHeight": 480,
            "DataCheckFreq": 30,
            "SendProtocol": [1,0,0,0,0,0,0,0],
            "CameraFOV": 90,
            "EularOrQuat": 0,
            "SensorPosXYZ": [0, 0, 0],
            "SensorAngQuat": [0,0,0,0],
            "SensorAngEular": [0,0,0],
            "otherParams": [200,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0]  // maxRange=200m
        }
    ]
}

ROS: 测距传感器数据不发布独立 ROS 话题,通过 Python vis.DistanceSensor 对象直接访问。

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\1.ImgSenorAPI\6.RangingImageDemo


Type 6 — 声音传感器(开发中,付费版)

采集的左右声道音频

项目 说明
用途 环境音频采集与分析(如环境音监测、声源定位、语音识别等)
获取原理 捕获并输出 RflySim3D 场景中的实时音频数据
输出格式 实时音频数据串流 (支持双声道, 48kHz采样)
DataWidth / DataHeight 无效
CameraFOV 无效
共享内存大小 不支持共享内存

otherParams 定义:

索引 参数 说明
[0] enableAudio 1: 开启并发送音频数据; 0: 停止发送音频数据

网络通信配置 (SendProtocol): | 索引 | 字段 | 说明 | |:-:|------|------| | [0] | sendMode | 1: UDP 传输协议 | | [5] | 端口号 | 音频数据传输的目标端口号 |

Config.json 示例

{
    "VisionSensors": [
        {
            "SeqID": 0,
            "TypeID": 6,                    // 声音传感器
            "TargetCopter": 0,
            "TargetMountType": 0,
            "DataWidth": 0,
            "DataHeight": 0,
            "DataCheckFreq": 30,            // 发送频率
            "SendProtocol": [0,127,0,0,1,28003,0,0], // UDP 端口 28003
            "CameraFOV": 0,
            "EularOrQuat": 0,
            "SensorPosXYZ": [0, 0, 0],
            "SensorAngQuat": [0,0,0,0],
            "SensorAngEular": [0,0,0],
            "otherParams": [1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0] // 1: 开启发送
        }
    ]
}

Python 输出: 通过自定义 Socket (Buffer Size: 204800,双声道, 48kHz) 接收 UDP 数据包进行音频解码或处理。

Demo 例程: [安装目录]\4.RflySimModel\3.CustExps\e7_ExternalSensors\e2_Voice_PyRec


Type 7 — 深度图转点云(付费版)

深度转点云可视化

项目 说明
用途 基于深度图反投影生成 3D 点云
获取原理 先渲染场景深度图,再通过相机内参(针孔模型)将每个像素反投影为 3D 点,同时可选地获取每个点的语义标注颜色
输出格式 Int16 编码的 XYZ [+ 语义颜色],每点 3 或 4 通道
坐标系 FLU (前-左-上), 相对于 AxisMask 设定的参考系
DataWidth / DataHeight 深度图分辨率 (像素),影响点云密度
CameraFOV 相机视场角 (度)
共享内存大小 1 + 8 + 9×4 + W×H×3×2 bytes

otherParams 定义:

索引 参数 说明
[0] maxDepth 最大深度距离 (米),超出此值的点被过滤
[1] step / debugMode >0 时开启调试模式(绑定 DebugPlane 显示),同时作为采样步长
[7] AxisMask 坐标系模式 (见下表)

SendProtocol[7] 定义:

含义
0 仅输出 XYZ(每点 3 通道)
>0 输出 XYZI(每点 4 通道),第 4 通道为 RGB555 编码的语义颜色

AxisMask 定义:

模式 说明
0 飞机坐标 使用绑定飞机的绝对位姿
1 传感器绝对坐标 使用传感器自身的绝对位姿
2 传感器相对坐标 使用传感器相对于起始点的位姿变化量

Python 输出: vis.Img[i]np.ndarray (N×3 或 N×4, int16, XYZ[I] 点云),可通过 Open3DShow 模块实时显示。取图流程同 Type 1TypeID 改为 7

ROS: 点云数据不通过 SDK 内置 ROS 话题发布,需用户自行转换为 sensor_msgs/PointCloud2

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\3.PointCloudAPI\4.DepthPointCloudDemo


Type 8 — 鱼眼相机

鱼眼相机输出

项目 说明
用途 捕获超广角/全景鱼眼图像
获取原理 在传感器位置放置全景立方体相机,同时渲染六个方向的图像,然后通过鱼眼投影模型合成为一张鱼眼图像
输出格式 RGB 彩色图 (W×H×3 bytes)
DataWidth / DataHeight 输出图像分辨率
CameraFOV 鱼眼视场角

otherParams 定义:

索引 参数 说明
[0] fisheyeType 鱼眼投影类型

Python 输出: vis.Img[i]np.ndarray (H×W×3, uint8, BGR 鱼眼图像)。取图流程同 Type 1TypeID 改为 8

ROS: /rflysim/sensor{SeqID}/fisheye · sensor_msgs/Image · 编码 bgr8

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\11.FishEyeDemo


Type 9 — 吊舱(付费版)

吊舱输出

项目 说明
用途 可控吊舱相机,支持姿态控制、角速度控制、目标跟踪、回中、光学变倍、测距及 AI 框选等功能
获取原理 使用电影级虚拟相机模拟吊舱,通过弹簧臂组件实现平滑运动。支持通过控制指令实时调整朝向(四元数 Slerp 插值),可配合目标跟踪自动锁定目标或 GPS 坐标
输出格式 RGB 彩色图 (W×H×3 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 初始视场角 (度),运行中可通过 bitmask 动态修改

初始化参数 (otherParams):

索引 参数 说明
[4] OpitcalBaseNum 光学变倍基数 (范围 4–1000,默认 4)
[5] disNum 测距最大距离 (米,默认 200)

吊舱控制 — bitmask 位掩码

吊舱通过 VisionSensorReqNew.bitmask 字段进行控制,每个功能对应一个位。多个功能可同时激活。

位 (bit) 功能 说明
1<<1 视场角 (FOV) 直接设置 CameraFOV 字段的值
1<<2 角度控制 吊舱平滑旋转到 SensorAngEuler / SensorAngQuat 指定的目标姿态,以 120°/s 的速度 Slerp 插值移动
1<<3 四元数模式 配合角度控制使用,以四元数方式指定目标姿态
1<<4 焦距 直接设置焦距值 (mm),通过 otherParams[0] 传入
1<<5 回中 吊舱平滑回到初始安装姿态(otherParams[1] > 0 时触发)
1<<6 角速度控制 以指定角速度持续旋转,通过 otherParams[2] (Pitch) 和 otherParams[3] (Yaw) 设置角速度 (°/s)
1<<7 光学变倍 焦距平滑过渡到 otherParams[4] × OpitcalBaseNum 的目标值
1<<8 目标跟踪 自动跟踪指定目标。otherParams[5] ≥ 0 时按 CopterID 跟踪;otherParams[5] < 0 时按 GPS 坐标 (otherParams[9-11]) 跟踪
1<<9 测距 从吊舱镜头中心发射射线,返回命中距离和命中点坐标
1<<10 图像类型切换 切换吊舱输出的图像类型,由 otherParams[7] 控制(见下表)
1<<11 AI 框选 启用 AI 目标检测功能,由 otherParams[8] 控制模式(见下表)

图像类型切换 (otherParams[7])

类型 说明
0 RGB 彩色 标准可见光图像(默认)
1 红外伪彩色 模拟红外热成像的伪彩色图像
2 红外灰度 模拟红外成像的灰度图像

AI 框选模式 (otherParams[8])

模式 说明
0 关闭 不执行 AI 检测
1 全目标框选 自动框选视野内所有 Copter 对象(排除自身载具),返回边界框
2 像素点选 检测 otherParams[9-10] 指定的像素坐标处的物体,返回该物体的边界框,并可作为跟踪目标

Python 输出: vis.Img[i]np.ndarray (H×W×3, uint8, BGR)。吊舱使用 VisionSensorReqNew 结构体控制(含 bitmask),通过 vis.sendUpdateUEImage(vsrNew) 发送控制指令。

ROS: /rflysim/sensor{SeqID}/img_cine · sensor_msgs/Image · 编码 bgr8

Demo 例程: [安装目录]\8.RflySimVision\2.AdvExps\e1_CameraKeyDemoOnUbuntu


Type 10 — 光流传感器

项目 说明
用途 光流速度估计 + 距地高度测量
获取原理 向地面发射射线测量距地高度;同时对比相邻帧图像像素位移来估算光流速度,支持真值模式(直接使用速度数据)和 OpenCV 模式(图像特征点追踪)
共享内存大小 1 + 8 + 8 + 1 + 4 + 8 + 1 + 12 = 43 bytes

otherParams 定义:

索引 参数 说明
[0] maxRange 最大距地高度测量距离 (米)
[1] OpticalFlowType 光流计算方式: 0=真值计算, 1=OpenCV
[2] maxCorners (仅 OpenCV) 最大角点数量 (默认 50)
[3] qualityLevel (仅 OpenCV) 角点质量阈值 (默认 0.3)
[4] minDistance (仅 OpenCV) 角点最小间距 (默认 7 pixels)

输出数据 (OpticalFlowParams):

字段 说明
time_usec Unix 时间戳
sensor_id 传感器 ID (= SeqID)
flow_x / flow_y 光流速度 (dpix/frame)
flow_comp_m_x / flow_comp_m_y 光流速度 (m/s)
quality 光流质量 (0–255)
ground_distance 距地高度 (米)
flow_rate_x / flow_rate_y 角速度补偿 (rad/s)

Python 输出: 光流数据通过 MAVLink 协议传输,在 vis.imu 相关结构中获取 OpticalFlow 数据。TypeID 设为 10

ROS: 光流数据不通过 SDK 内置 ROS 话题发布,需用户自行使用 MAVLink ROS 桥接。

Demo 例程: [安装目录]\4.RflySimModel\3.CustExps\e7_ExternalSensors\e3_Opticalflow_UE


Type 20 — LiDAR(机体坐标系)

激光雷达坐标系点云输出

项目 说明
用途 射线追踪 LiDAR 仿真,输出机体坐标系下的点云
获取原理 按配置的水平/垂直角度范围和分辨率,并行发射大量射线进行碰撞检测,将命中点坐标转换到传感器机体坐标系,并编码每个点的语义标注 (RGB555)
输出格式 Int16 编码的 XYZI (每点 4 通道)
坐标系 机体坐标系 (传感器本体)
共享内存大小 1 + 8 + 9×4 + 2×4×W×H bytes

otherParams 定义:

索引 参数 说明
[0] distRange 最大测距距离 (米),默认 200m
[1] distPrec 距离精度 (保留)
[2] levelLeftAng 水平扫描左边界角度 (度)
[3] levelRightAng 水平扫描右边界角度 (度)
[4] horiDownAng 垂直扫描下边界角度 (度)
[5] horiUpAng 垂直扫描上边界角度 (度)
[6] GaussNoise0 高斯噪声参数 0 (保留)
[7] AxisMask 坐标系模式 (同 Type 7 的 AxisMask)

SendProtocol[7] 定义:

含义
0 仅输出 XYZ(跳过强度通道)
>0 输出 XYZI(第 4 通道为 RGB555 语义颜色)

扫描范围: DataWidth 列 × DataHeight 行,角度范围由 otherParams[2–5] 定义。

Python 输出: vis.Img[i]np.ndarray (N×3/4, int16, XYZI 点云),可通过 Open3DShow 模块显示。取图流程同 Type 1

Config.json 示例

{
    "VisionSensors": [{
        "SeqID": 0,
        "TypeID": 20,             // LiDAR 机体坐标系
        "TargetCopter": 1,
        "TargetMountType": 0,
        "DataWidth": 900,          // 水平扫描 900 列
        "DataHeight": 32,          // 垂直扫描 32 行
        "DataCheckFreq": 10,       // 10Hz
        "SendProtocol": [0,0,0,0,0,0,0,0],
        "CameraFOV": 90,
        "EularOrQuat": 0,
        "SensorPosXYZ": [0, 0, -0.3],  // 安装在载具上方 0.3m
        "SensorAngQuat": [0,0,0,0],
        "SensorAngEular": [0,0,0],
        "otherParams": [200, 0.05, -45, 45, -20, 20, 0, 0, 0,0,0,0,0,0,0,0]
        // [0]=最大距离200m [2-5]=水平±45° 垂直-20°~+20°
    }]
}

ROS: 点云数据不通过 SDK 内置 ROS 话题发布,需用户自行转换为 sensor_msgs/PointCloud2

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\8.LidarAPIDemo\2.UDPDirectClientServer


Type 21 — LiDAR(世界坐标系)

世界坐标系点云输出

Type 20 参数完全一致,唯一区别:

项目 Type 20 Type 21
输出坐标系 机体坐标系 世界坐标系

Python/ROS 接口同 Type 20TypeID 改为 21

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\8.LidarAPIDemo\3.UDPDirectClientServerType5


Type 22 — LiDAR(DJI 花瓣扫描)

mid40激光雷达 大疆激光雷达的实验数据展示

项目 说明
用途 DJI 风格非重复性花瓣扫描 LiDAR
获取原理 模拟 DJI Livox 系列的 8 字形花瓣扫描模式,每帧在花瓣路径上发射射线进行碰撞检测,多帧累积后按设定频率批量输出点云
共享内存大小 1 + 8 + 9×4 + 2×4×W×H bytes

otherParams 定义:

索引 参数 说明
[0] distRange 最大测距距离 (米),默认 200m
[1] d1 圆弧弦高(弧最高点与最低点之差)
[2] xCor X 方向修正系数 (默认 1.4)
[3] LeftRadCor 左弧半径修正系数 (默认 1.18)
[4] EightNum 8 字形花瓣数量 (默认 1)
[5] FlowerNum 每朵花瓣中的 8 字形数量 (默认 1)
[6] randAngle 随着扫描图案增加的随机偏移角度 (度)
[7] AxisMask 坐标系模式 (同 Type 7 的 AxisMask)

DataWidth / DataHeight 含义变化: - DataWidth: 半边花瓣的总点数 - DataHeight: 花瓣行数 - 每帧实际扫描点数 = DataWidth × DataHeight × 3 - CameraFOV 在此类型中用作圆弧弦长计算: 弦长半 = CameraFOV / 4

Python/ROS 接口同 Type 20TypeID 改为 22

Demo 例程: [安装目录]\8.RflySimVision\2.AdvExps\e0_AdvApiExps\.7LidarLivoxDemo


Type 23 — LiDAR Mid-360

mid360激光雷达输出

项目 说明
用途 Livox Mid-360 风格 360° 旋转扫描 LiDAR
获取原理 模拟 Livox Mid-360 的 16 线旋转扫描模式,每帧发射 17,408 条射线 (16×272×4) 进行碰撞检测,并逐帧旋转扫描角度
强制分辨率 DataWidth = 64, DataHeight = 272 (参数修改无效)
每帧射线数 16 × 272 × 4 = 17,408
共享内存大小 1 + 8 + 4×9 + 2×4×midPointNum bytes

otherParams 定义:

索引 参数 说明
[0] distRange 最大测距距离 (米)

Python/ROS 接口同 Type 20TypeID 改为 23

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\10.Mid360Demo


Type 30 — 简易视觉传感器

目标识别框 传感器输出

项目 说明
用途 视锥体内目标检测,输出 2D 边界框
获取原理 通过距离剔除、视域角度剔除和射线可视性检测判断目标是否可见,然后将可见目标的 3D 边界框投影到屏幕空间输出 2D 矩形框
共享内存大小 1 + 8 + 4 + maxTargets × sizeof(SimpleVisionDataStruct) bytes

otherParams 定义:

索引 参数 说明
[0] maxRange 最大检测距离 (米)
[1] maxTargets 最大目标数量 (影响共享内存大小)

输出 (SimpleVisionDataStruct):

字段 说明
CopterID 目标飞机 ID
Credibility 置信度(边界框面积占比)
BoxPositionInScreen 屏幕空间 2D 边界框 (xMin, yMin, xMax, yMax)

Python 输出: vis.Img[i] → 结构化数据,包含 CopterIDCredibilityBoxPositionInScreen。取图流程同 Type 1TypeID 改为 30

ROS: 检测数据不通过 SDK 内置 ROS 话题发布,通过 Python vis.Img[i] 直接访问。

配置前提

Type 30 简易视觉传感器必须和 Type 1 RGB 传感器同时写在同一个 Config.jsonVisionSensors 数组中。若只配置 Type 30,不同时配置 RGB 传感器,SDK 侧无法拿到简易视觉检测数据。

Demo 例程: [安装目录]\8.RflySimVision\2.AdvExps\e7_ObjDetectYolo\SimpleSensorBaseOnYolo


Type 31 — 简易雷达传感器

项目 说明
用途 全向目标检测,输出目标相对位置
获取原理 检测指定距离范围内的所有目标,通过射线检测验证视线可达性,输出目标在传感器坐标系下的三维相对位置
共享内存大小 1 + 8 + 4 + maxTargets × sizeof(SimpleRadarDataStruct) bytes

otherParams 定义:

索引 参数 说明
[0] maxRange 最大检测距离 (米)
[1] maxTargets 最大目标数量 (影响共享内存大小)

输出 (SimpleRadarDataStruct):

字段 说明
CopterID 目标飞机 ID
RelativePosition 目标在传感器坐标系下的相对位置 (米)

与 Type 30 的区别: 无视域角度限制(全向检测),无 2D 投影。

Python 输出: vis.Img[i] → 目标列表,每个元素为 (CopterID, PosX, PosY, PosZ)PosX/PosY/PosZ 是目标在传感器坐标系下的三维相对位置,单位为米。

ROS: 检测数据不通过 SDK 内置 ROS 话题发布,通过 Python vis.Img[i] 直接访问。

配置前提

Type 31 简易雷达传感器必须和 Type 1 RGB 传感器同时写在同一个 Config.jsonVisionSensors 数组中。若只配置 Type 31,不同时配置 RGB 传感器,SDK 侧无法拿到简易雷达目标数据。

Config.json 示例

下例先创建一个常规 RGB 传感器,再创建绑定在同一架飞机上的简易雷达传感器。Type 31 的输出仍是目标相对位置列表,但配置中应保留标准的 DataWidthDataHeightCameraFOV 字段;otherParams[0] 为最大探测距离,otherParams[1] 为最大目标数量。Type 31 推荐使用 UDP 网络传输模式,并为该传感器设置独立端口。

{
    "VisionSensors": [
        {
            "SeqID": 1, // 视觉传感器序号。填 0 时自动递增排序。
            "TypeID": 1, // 1: RGB 图像
            "TargetCopter": 1, // 传感器绑定的 CopterID,免费版只支持绑定 1 号飞机
            "TargetMountType": 0, // 0: 固定飞机几何中心
            "DataWidth": 640,
            "DataHeight": 480,
            "DataCheckFreq": 10,
            "SendProtocol": [0, 0, 0, 0, 0, 0, 0, 0],
            "CameraFOV": 60,
            "EularOrQuat": 0,
            "SensorPosXYZ": [0.50, 0, 0.5],
            "SensorAngQuat": [0, 0, 0, 0],
            "SensorAngEular": [0, 0, 0],
            "otherParams": [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
        },
        {
            "SeqID": 2, // 简易雷达传感器序号
            "TypeID": 31, // 31: 简易雷达
            "TargetCopter": 1,
            "TargetMountType": 0,
            "DataWidth": 640,
            "DataHeight": 480,
            "DataCheckFreq": 10,
            "SendProtocol": [1, 127, 0, 0, 1, 10001, 0, 0],
            "CameraFOV": 60,
            "EularOrQuat": 0,
            "SensorPosXYZ": [0.50, 0, 0.5],
            "SensorAngQuat": [0, 0, 0, 0],
            "SensorAngEular": [0, 0, 0],
            "otherParams": [200, 100, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
            // Type 31(简易雷达): [0]=最大检测距离(m), [1]=最大目标数量
        }
    ]
}

Python 读取例程

import time
import VisionCaptureApi

vis = VisionCaptureApi.VisionCaptureApi()

# 1. 加载包含 Type 31 的 Config.json
vis.jsonLoad()

# 2. 向 RflySim3D 发送传感器请求
if not vis.sendReqToUE4():
    raise RuntimeError("RflySim3D 未响应传感器请求")

# 3. 开启共享内存/UDP 数据读取线程
vis.startImgCap()

# 4. 找到 Type 31 传感器在 VisSensor/Img 数组中的索引
radar_idx = next(
    i for i, sensor in enumerate(vis.VisSensor)
    if sensor.TypeID == 31
)

while True:
    time.sleep(0.05)
    if not vis.hasData[radar_idx]:
        continue

    # Type 31 输出格式:
    # vis.Img[radar_idx] = [
    #     (CopterID, PosX, PosY, PosZ),
    #     ...
    # ]
    # PosX/PosY/PosZ 为目标在传感器坐标系下的相对位置,单位 m。
    with vis.Img_lock[radar_idx]:
        targets = list(vis.Img[radar_idx])

    for copter_id, pos_x, pos_y, pos_z in targets:
        distance = (pos_x ** 2 + pos_y ** 2 + pos_z ** 2) ** 0.5
        print(
            f"CopterID={copter_id}, "
            f"RelativePosition=({pos_x:.2f}, {pos_y:.2f}, {pos_z:.2f}) m, "
            f"Distance={distance:.2f} m"
        )

输出说明

Type 31 是全向相对位置传感器,不做视场角裁剪,也不输出 2D 框。若需要图像视野内的目标框,请使用 Type 30 简易视觉传感器。


Type 40 — 红外灰度图(付费版)

红外灰度图

项目 说明
用途 模拟红外成像的灰度图
获取原理 在传感器位置放置虚拟相机,通过红外成像材质将场景渲染为模拟红外辐射的灰度图像
输出格式 单通道灰度 (W×H×1 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Python 输出: vis.Img[i]np.ndarray (H×W, uint8, 单通道红外灰度)。取图流程同 Type 1TypeID 改为 40

ROS: /rflysim/sensor{SeqID}/img_Infrared_Gray · sensor_msgs/Image · 编码 mono8

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\1.ImgSenorAPI\7.InfraredgrayThermalImageDemo


Type 41 — 红外伪彩色图(付费版)

热力彩色图

项目 说明
用途 模拟红外热成像的伪彩色图(热力图)
获取原理 在传感器位置放置虚拟相机,通过红外热成像材质将场景温度分布渲染为伪彩色图像,冷区与热区以不同色调呈现
输出格式 RGB 彩色图 (W×H×3 bytes)
DataWidth / DataHeight 图像分辨率 (像素)
CameraFOV 相机视场角 (度)
otherParams 无专用参数

Python 输出: vis.Img[i]np.ndarray (H×W×3, uint8, BGR 红外伪彩色图)。取图流程同 Type 1TypeID 改为 41

ROS: /rflysim/sensor{SeqID}/img_Infrared · sensor_msgs/Image · 编码 bgr8

Demo 例程: [安装目录]\8.RflySimVision\0.ApiExps\1-UsageAPI\1.ImgSenorAPI\7.InfraredgrayThermalImageDemo


IMU 传感器数据 (来自 CopterSim)

IMU 数据并非由 RflySim3D 产生,而是通过 UDP 从 CopterSim 飞控仿真器获取。VisionCaptureApi 提供了统一的请求与接收接口。

数据结构 (imuDataCopter)

字段 类型 说明
checksum int 校验位,固定 1234567898
seq int 消息序号
timestmp double 仿真时间戳 (秒)
acc[3] float[3] 三轴加速度 (m/s²),机体坐标系
rate[3] float[3] 三轴角速度 (rad/s),机体坐标系

C++ 结构体格式: 2i1d6f,总大小 40 bytes。CopterSim 通过 UDP 端口 30100 + (copterID-1)*2 接收请求,回传到端口 31000 + copterID - 1

Python 请求与读取

import VisionCaptureApi

vis = VisionCaptureApi.VisionCaptureApi()
vis.jsonLoad()
vis.sendReqToUE4()
vis.startImgCap()

# 请求 CopterSim 1号飞机的 IMU 数据(默认200Hz)
vis.sendImuReqCopterSim(copterID=1)

# 读取 IMU 数据
while True:
    if vis.hasIMUData:
        print('时间:', vis.imu.timestmp)       # 仿真时间 (秒)
        print('加速度:', vis.imu.acc)           # [ax, ay, az] m/s²
        print('角速度:', vis.imu.rate)          # [gx, gy, gz] rad/s

ROS 数据

话题 消息类型 说明
/rflysim/imu sensor_msgs/Imu 加速度 + 角速度,frame_id = "imu"

ROS 坐标映射 (机体→ROS):

IMU 字段 ROS linear_acceleration ROS angular_velocity
[0] (x) -acc[0] rate[0]
[1] (y) acc[1] -rate[1]
[2] (z) -acc[2] -rate[2]

ROS2 区分: ROS1 使用 rospy.Duration(imuStmp) 设置时间戳;ROS2 使用 rclpy.duration.Duration(seconds=imuStmp) 并分别赋值 stamp.secstamp.nanosec

Demo 例程: [安装目录]\RflySimAPIs\8.RflySimVision\0.ApiExps\1-UsageAPI\2.ImuSenorAPI


附录: 传感器类型速查表

TypeID 名称 类别 免费版 获取方式 输出格式
1 RGB 图像 图像 虚拟相机渲染 RGB, 3ch
2 深度图 图像 虚拟相机深度渲染 16-bit, 2ch
3 灰度图 图像 虚拟相机渲染 Gray, 1ch
4 分割图 图像 语义标注渲染 RGB, 3ch
5 测距 射线 射线碰撞检测 float 距离
6 声音 音频 场景环境音捕获 音频串流
7 深度点云 点云 深度图反投影 XYZ[I], 3/4ch
8 鱼眼 图像 全景相机 + 鱼眼投影 RGB, 3ch
9 吊舱 图像 可控吊舱相机 RGB, 3ch
10 光流 传感器 射线+图像帧间对比 MAVLink 光流
20 LiDAR (机体) 点云 多射线并行碰撞检测 XYZI, 4ch
21 LiDAR (世界) 点云 多射线并行碰撞检测 XYZI, 4ch
22 LiDAR (DJI) 点云 花瓣扫描碰撞检测 XYZI, 4ch
23 Mid-360 点云 旋转扫描碰撞检测 XYZI, 4ch
30 简易视觉 检测 视锥剔除 + 射线检测 2D BBox
31 简易雷达 检测 距离剔除 + 射线检测 3D 相对位置
40 红外灰度 图像 红外成像材质渲染 Gray, 1ch
41 红外伪彩色 图像 红外热成像渲染 RGB, 3ch