RflySimSDK v3.08
RflySimSDK说明文档
载入中...
搜索中...
未找到
传统机械式激光雷达(输出点云为激光雷达坐标系)

激光雷达坐标系点云输出

1. 功能概述

1.1 支持的功能操作

传感器输出

  • 输出点云数据,默认采用激光雷达坐标系。点云中每个点由三维空间坐标 (x, y, z) 表示。
  • 支持高精度深度信息采集,分辨率和刷新频率可配置。
  • 点云数据通过共享内存或 UDP 方式传输,便于集成到外部应用。

应用场景

  • **自主导航与避障**:通过实时点云数据生成环境模型,用于无人机或机器人导航。
  • **环境建模**:生成三维环境地图,用于地形测绘或仿真训练。
  • **目标检测与跟踪**:结合点云和图像数据识别场景中的特定目标。

1.2 使用示例

配置文件添加传感器 以下是配置文件 Config.json 的示例代码,用于添加激光雷达传感器:

{
"VisionSensors":[
{
"SeqID":0, //视觉传感器序号0 1 2 3 ...排序。如果填0,则自动递增排序。
"TypeID":20, //输出点云为激光雷达坐标系
"TargetCopter":1, //传感器绑定的CopterID号
"TargetMountType":0,
"DataWidth":900, //激光雷达一个ring内的点云个数
"DataHeight":32,//激光雷达线束数量
"DataCheckFreq":10,//点云发布频率(hz)
"SendProtocol":[1,0,0,0,0,0,0,0],
"CameraFOV":90, //在激光雷达传感器上无作用
"EularOrQuat":0,
"SensorPosXYZ":[0,0,-0.3],
"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] //[激光最远距离(m),精度(m),水平扫描角度 下限值(度),水平扫描角度上限值(度),垂直扫描角度下限值(度),垂直扫描角度上限值(度),预留,预留];
}
]
}

激光雷达水平分辨通过DataWidth和水平扫描角度范围体现,垂直分辨率通过处置扫描角度体现(如上配置的传感器水平角分辨率=90/900,垂直角分辨率=40/32),以上角度值都是用degree表示。

Python 调用传感器接口 取图显示相关代码:

vis = VisionCaptureApi.VisionCaptureApi() # 创建一个视觉传感器实例
vis.jsonLoad() # 加载Config.json中的传感器配置文件
isSuss = vis.sendReqToUE4() # 向RflySim3D发送取图请求
vis.startImgCap() # 开启取图
vis.hasData[i] # 图片i数据是否更新
vis.Img[i] # 图片i数据
show3d=Open3DShow.Open3DShow() # 创建3D点云显示实例
show3d.CreatShow(0) # 创建点云显示窗口
show3d.UpdateShow(vis.Img[0]) # 更新点云

例程链接

1.3 现实中的机械式激光雷达传感器


2. 传感器配置

2.1 传感器安装

参数名称 取值范围 含义
TargetMountType 0: 固定载具上(相对几何中心);1: 固定载具上 (相对底部中心);2: 固定地面上(监控);3:相对地面坐标系的吊舱相机,固定飞机上,但相机姿态不随飞机变化(地面坐标系);4:将传感器附加到另外一个传感器上 决定传感器的所属载体对象及安装方式。
TargetCopter 目标传感器ID(默认为0)或目标实体对象 ID (默认 1) 决定传感器安装方式后,选择目标测量对象ID。传感器固定在载具或地面上时,该值对应目标载具或其它实体对象的CopterID;传感器固定在其它传感器上时,该值对应目标传感器**SeqID**。
SensorPosXYZ [x, y, z] (单位:米) 相对于传感器所属载体对象的安装位置。
EulerOrQuat 0: 欧拉角;1: 四元数 选择安装姿态的表示方式。
SensorAngEular [roll, pitch, yaw] (弧度) 安装姿态,欧拉角方式表示。
SensorAngQuat [q0, q1, q2, q3] 安装姿态,四元数方式表示。

2.2 网络通信配置

参数名称 取值范围 含义
SendProtocol [mode, IP, port, …] 配置数据传输协议,支持共享内存和 UDP。
SendProtocol[0] 0: 共享内存;1: UDP 压缩传输 选择传输方式。
SendProtocol[5] 端口号 数据传输的目标端口号。

2.3 传感器技术规格

技术参数 配置值 说明
SeqID 0 每个传感器在 RflySim3D 内的唯一编号。若设为0,将自动确认序号并递增排序
TypeID 20 传感器类型,激光雷达传感器(机械式扫描,激光雷达本体坐标系输出)。
DataHeight 32 激光雷达线束数量。
DataWidth 900 每圈点数(相当于每帧点数)
DataCheckFreq 10 Hz 数据刷新频率,默认 10Hz,最大支持取决于RflySim3D刷新率
otherParams[0] 200 激光雷达的最大测量范围(米)。
otherParams[1] 0.05 点云数据精度(米)。
otherParams[2-3] [-45, 45] 水平扫描角度范围(度)。
otherParams[2-3] [ -20, 20] 垂直扫描角度范围(度)。