MoSA 是面向实时机器人系统的高性能运动感知框架,专门为 ROBOMASTER 比赛激光雷达应用场景设计。它受到香港大学 MARS Lab 提出的 M-Detector 启发,并在其基础上完成深度工程化与系统级优化,重点关注:
- 极低延迟实时监测
- CPU-only 高吞吐,强并行友好
- 稳定输出 动态点云 + AABB
- 无学习依赖、无先验假设
MoSA 可在无语义、无训练数据的条件下稳定检测动态目标,并作为下游感知、规划、规避、检测等模块基础输入。
- 原作者单位:The University of Hong Kong, MARS Lab
- 论文:Moving Event Detection from LiDAR Point Streams(Nature Communications, 2024)
MoSA 保留并致谢原作者的算法思想与论文贡献,在实现层面对性能、并行模型与工程接口进行了系统性重构。
- Ubuntu 22.04
- ROS2 Humble
- PCL >= 1.8
- Eigen >= 3.3.4
- oneTBB (
libtbb-dev)
安装示例:
sudo apt install libpcl-dev libeigen3-dev libtbb-dev推荐目录结构:
ros2_ws/
src/
mosa/
Important
若使用 Livox 设备,需要确保 livox_interfaces 已存在并被 source(建议由 Livox ROS2 驱动工作空间单独提供)。
git clone https://github.com/BreCaspian/MoSA.gitmkdir -p ~/ros2_ws/src
cp -r MoSA ~/ros2_ws/src/mosa
cd ~/ros2_ws
colcon build --symlink-install
source install/setup.bashros2 launch mosa mid70.launch.py其他内置设备配置:
ros2 launch mosa mid360.launch.py
ros2 launch mosa horizon.launch.py
ros2 launch mosa avia.launch.py默认使用 rviz/mosa.rviz。关闭 RViz:
ros2 launch mosa mid70.launch.py rviz:=falseTip
RViz 仅影响显示,不影响算法输出与性能。
点云输入:
- Livox CustomMsg(默认):
- 话题:
/livox/lidar - 参数:
dyn_obj/use_livox_custom: true
- 话题:
- 标准 PointCloud2:
- 话题:
dyn_obj/points_topic - 参数:
dyn_obj/use_livox_custom: false
- 话题:
里程计输入:
- 话题:
dyn_obj/odom_topic - 默认:
/aft_mapped_to_init
MoSA 仅依赖短时连续位姿稳定性,不要求全局闭环或高精度地图。
| 话题 | 类型 | 说明 |
|---|---|---|
/mosa/point_out |
PointCloud2 | 点级动态结果(最低延迟) |
/mosa/frame_out |
PointCloud2 | 帧级稳定动态结果 |
/mosa/std_points |
PointCloud2 | 静态点云 |
/mosa/aabb |
MarkerArray | 动态目标 AABB |
可选文件输出:
dyn_obj/out_filedyn_obj/out_file_origindyn_obj/cluster_out_filedyn_obj/time_filedyn_obj/time_breakdown_file
当 LiDAR 完全静止且坐标系稳定时,可关闭里程计:
dyn_obj/use_odom: false
dyn_obj/static_pos: [0.0, 0.0, 0.0]
dyn_obj/static_quat: [1.0, 0.0, 0.0, 0.0]Caution
仅适用于传感器完全静止场景。传感器运动会引入明显误检。
config/base/base.yaml 包含与设备无关的核心算法参数,建议作为全局基线。
关键参数分类:
- 输入:
use_livox_custom、points_topic、use_odom、odom_topic - 时序/缓存:
frame_dur、buffer_delay、points_num_perframe - 动态稳定化:
dyn_points_stable_en、dyn_points_accu_limit、dyn_points_voxel - 追踪与输出:
track_enable、track_min_hits、track_max_age、track_gate、aabb_alpha - 性能:
cluster_async、cluster_queue_size
| 设备 | 需要重点调整的参数 |
|---|---|
| MID70 | fov_*, points_num_perframe, frame_dur, max_pixel_points |
| MID360 | 同 MID70,点密度更高 |
| Horizon | 横向 FOV 大,需调整 fov_* |
| 通用 PC2 | use_livox_custom=false, points_topic, frame_dur |
通用 PC2 示例:config/pc2/pc2.yaml
推荐加载方式:
ros2 run mosa dynfilter --ros-args \
--params-file config/base/base.yaml \
--params-file config/mid70/mid70.yaml- 所有输出统一
frame_id = dyn_obj/frame_id - 使用里程计时应为稳定全局系(如
map/camera_init)
- 使用扫描结束时刻
scan_end_time - 点云与 AABB 时间戳一致
- 轴对齐包围盒(AABB)
- 中心:
pose.pose.position - 尺寸:存储于
pose.covariance - Marker:绿色线框立方体
id:跟踪 ID- 不包含语义类别
ros2 launch mosa cal_recall.launch.py \
dataset:=0 dataset_folder:=/path/to/dataset \
start_se:=0 end_se:=0 start_param:=0 end_param:=0 is_origin:=false- 检查
/mosa/point_out是否有频率输出 - 若
/livox/lidar同时存在 CustomMsg 和 PointCloud2,请确认订阅类型一致
Tip
可用 ros2 topic info --verbose /livox/lidar 确认实际发布类型。
- 话题类型冲突时请用
ros2 topic info --verbose /livox/lidar查看真实类型
- 确认输入点云频率与
dyn_obj/frame_dur匹配 - 适当调大
dyn_obj/dyn_points_accu_limit与dyn_obj/dyn_points_voxel - 检查是否启用
dyn_obj/use_odom,并确保里程计可用
- 确认
/mosa/aabb有发布(MarkerArray) - 检查
dyn_obj/track_enable是否开启 - 若启用
cluster_async=true,/mosa/frame_out不会输出属于正常现象
在保持算法逻辑不变的前提下,进行了多轮等价优化,主要包括:
- 调整 TBB 粒度与并行合并,减少任务调度开销
- 动态点与聚类链路内存池化,降低频繁分配
- DepthMap 采用 dirty list 重置与像素桶化批更新
- Case2/Case3 判定访问局部化,减少重复访问
- 复用投影结果,降低
atan2f计算占比
效果(同类场景下 VTune 采样对比):
- CPU Time 从约 166s 降至约 60s
- 整体提升约 64%(约 2.8×)
VTune 性能演进对比表
说明:4 次测试运行参数一致,但输入点云负载仍可能存在差异; Scheduling / Task Count / Overhead 的变化可视为真实优化效果。
| 序号 | Elapsed (s) | CPU Time (s) | Effective (s) | Spin (s) | Overhead (s) | Scheduling (s) | 线程数 | Top 1 Hotspot(CPU / 占比) | Top 2 Hotspot(CPU / 占比) | Top 3 Hotspot(CPU / 占比) | tbb Task Time (s) | Task Count | Avg Task (s) | 有效物理核利用率 |
|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
| 1 | 299.586 | 166.540 | 159.026 | 1.788 | 5.726 | 5.726 | 31 | Case2DepthConsistencyCheck 38.369 / 23.0% | Buffer2DepthMap 23.842 / 14.3% | Case3DepthConsistencyCheck 17.887 / 10.7% | 132.975 | 93,603 | 0.001 | 5.7% (0.804/14) |
| 2 | 358.072 | 130.160 | 129.076 | 0.749 | 0.335 | 0.335 | 31 | Buffer2DepthMap 29.642 / 22.8% | Case2DepthConsistencyCheck 27.175 / 20.9% | Case3DepthConsistencyCheck 10.240 / 7.9% | 88.658 | 37,077 | 0.002 | 3.9% (0.540/14) |
| 3 | 340.298 | 60.450 | 59.900 | 0.500 | 0.050 | 0.050 | 31 | Buffer2DepthMap 19.983 / 33.1% | SphericalProjection 4.618 / 7.6% | __atan2f 3.943 / 6.5% | 18.193 | 18,771 | 0.001 | 1.8% (0.257/14) |
| 4 | 331.952 | 59.830 | 59.170 | 0.590 | 0.070 | 0.070 | 31 | Buffer2DepthMap 19.215 / 32.1% | SphericalProjection 5.370 / 9.0% | __atan2f 4.035 / 6.7% | 19.046 | 18,304 | 0.001 | 1.9% (0.261/14) |
Tip
所有与性能优化相关的完整分析数据与报告已随 Release v1.1.0 一并发布。
你可以将 Release 中的 VTune 分析结果下载到本地
在 已正确安装 Intel® VTune™ Profiler 的环境下,使用如下命令直接打开最终一次热点分析结果:
vtune-gui vtune_hotspots_mosa_04本项目采用 GPL-3.0 许可证发布,任何分发与衍生作品必须遵守 GPL-3.0 的条款。
原作者:
- Huajie Wu — wu2020@connect.hku.hk
- Yihang Li — yhangli@connect.hku.hk
MoSA 在工程实现层面对原方法进行了优化与扩展,完整保留算法来源与作者署名。
联系人: Yuzhuo Yao — yaoyuzhuo6@gmail.com
