ROS合集(六)SVIn2 点云地图与 3D Tiles 可视化【预览版】

发布于:2025-05-24 ⋅ 阅读:(12) ⋅ 点赞:(0)

SLAM 点云发布与 3D Tiles 可视化流程

本文记录如何通过 ROS 定时发布点云并自动保存为 .ply 文件,随后由 Python 脚本实时转换为 Cesium 支持的 3D Tiles 格式,并部署到 Web 可视化平台中,支持版本记录与更新。


image-20250512105827690

1. ROS 定时发布与保存 .ply

1.1 初始化发布器

在构造函数中初始化各类发布器、输出目录、定时器:

Publisher::Publisher(ros::NodeHandle& nh) {
  nh.param("save_threshold", save_threshold_, 5);
  std::string pkg = ros::package::getPath("pose_graph");
  output_dir_ = pkg + "/reconstruction_results";
  fs::create_directories(output_dir_);

  pub_matched_points_ = nh.advertise<sensor_msgs::PointCloud>("match_points", 100);
  pub_gloal_map_ = nh.advertise<sensor_msgs::PointCloud2>("global_map", 1, true);

  update_timer_ = nh.createTimer(
    ros::Duration(1),
    &Publisher::updatePublishGlobalMap,
    this
  );
}
Publisher::Publisher(ros::NodeHandle& nh) {
  // 从参数服务器读取,或使用默认
  nh.param("save_threshold",   save_threshold_, 5);
  // 输出目录:package 下的 reconstruction_results
  std::string pkg = ros::package::getPath("pose_graph");
  output_dir_ = pkg + "/reconstruction_results";
  fs::create_directories(output_dir_);
  // 初始化各个话题的发布者
  pub_matched_points_ = nh.advertise<sensor_msgs::PointCloud>("match_points", 100);
  // pub_gloal_map_ = nh.advertise<sensor_msgs::PointCloud2>("global_map", 2);
  pub_gloal_map_ = nh.advertise<sensor_msgs::PointCloud2>("global_map", 1, true);
  // Timer for periodic global-map publishing
  update_timer_ = nh.createTimer(
    ros::Duration(1),                        // 每 1s 发布一次
    &Publisher::updatePublishGlobalMap,      // 回调成员方法
    this                                     // 绑定 this 指针
  );

1.2 定时更新与保存

每秒触发一次回调函数,发布全局地图并按阈值条件保存点云:

void Publisher::updatePublishGlobalMap(const ros::TimerEvent& event) {
  // 1) 获取最新全局地图
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr global_map_pcl(new pcl::PointCloud<pcl::PointXYZRGB>);
  pointcloud_callback_(global_map_pcl);

  // 2) 发布到 ROS 话题
  if (!global_map_pcl->empty()) {
    sensor_msgs::PointCloud2 msg;
    pcl::toROSMsg(*global_map_pcl, msg);
    msg.header.frame_id = "world";
    msg.header.stamp = ros::Time::now();
    publishGlobalMap(msg);
  }
    // 3) 根据阈值决定是否保存 PLY
  update_count_++;
  if (!global_map_pcl->empty() && update_count_ % save_threshold_ == 0) {
    savePointCloudToFile(global_map_pcl);
  }
}

1.3 保存 .ply 文件

使用 .tmp 临时文件+原子重命名机制保证写入完整性:

void Publisher::savePointCloudToFile(const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud) {
  // 获取当前时间,并按 YYYYMMDDHHMMSS 格式命名
  ros::Time now = ros::Time::now();
  std::time_t t = now.sec;
  std::tm tm_info;
  // 推荐使用线程安全版本
  localtime_r(&t, &tm_info);

  std::ostringstream oss;
  oss << output_dir_ << "/map_"
      << std::put_time(&tm_info, "%Y%m%d%H%M%S")
      << ".tmp";
  std::string tmp_filepath = oss.str();

  // 构造最终文件名
  std::string final_filepath = tmp_filepath;
  final_filepath.replace(
    final_filepath.find(".tmp"), 4, ".ply"
  );

  // 1. 保存到临时文件
  if (pcl::io::savePLYFileBinary(tmp_filepath, *cloud) == 0) {
    ROS_INFO_STREAM("Saved TEMP PLY: " << tmp_filepath);
  } else {
    ROS_ERROR_STREAM("Failed to save TEMP PLY: " << tmp_filepath);
    return;
  }

  // 2. 原子重命名
  std::error_code ec;
  fs::rename(tmp_filepath, final_filepath, ec);
  if (ec) {
    ROS_ERROR_STREAM("Failed to rename tmp to ply: " << ec.message());
    return;
  }
  ROS_INFO_STREAM("Saved PLY: " << final_filepath);
}

2. .ply 转换为 3D Tiles(Python 脚本)

利用 watchdog 监听 reconstruction_results 目录,并调用 py3dtiles.convert 自动转换:

#!/usr/bin/env python3
# -*- coding: utf-8 -*-
"""
convert_ply.py  ———— 版本子目录 + 更新列表
"""

import time, shutil, logging
from pathlib import Path
from watchdog.observers import Observer
from watchdog.events import FileSystemEventHandler
from py3dtiles.convert import convert

# 配置
IN_DIR        = Path("~/cesium-deepsea/SLAM/SVln2/svin_ws/src/SVIn/pose_graph/reconstruction_results").expanduser()
TMP_DIR       = Path("/data/ply/3dtiles_tmp")
TMP_ROOT      = Path("/data/ply/3dtiles_tmp")
WWW_ROOT      = Path("/var/www/html/pointcloud")
VERSIONS_LIST = WWW_ROOT/"updates.txt"
POLL_INTERVAL = 5

logging.basicConfig(level=logging.INFO, format="%(asctime)s %(levelname)s: %(message)s")

def process_ply(ply_path: Path):
    name = ply_path.name
    if not name.endswith(".ply") or ".processing" in name or ".done" in name:
        return
    base = name[:-4]
    proc = ply_path.with_name(f"{base}.processing.ply")
    ply_path.rename(proc)

    logging.info(f"⟳ Converting {base}")
    # 1) 准备临时目录
    tmp_dir = TMP_ROOT/base
    if tmp_dir.exists(): shutil.rmtree(tmp_dir)
    tmp_dir.mkdir(parents=True, exist_ok=True)

    # 2) 转换
    try:
        convert(files=str(proc), outfolder=str(tmp_dir),
                overwrite=True, jobs=4, cache_size=512,
                rgb=True, use_process_pool=True, verbose=False)
    except Exception as e:
        logging.error(f"✗ Conversion failed: {e}")
        proc.rename(ply_path)
        return
    logging.info(f"✔ Done {base}")

    # 3) 部署到版本子目录
    dest = WWW_ROOT/base
    if dest.exists(): shutil.rmtree(dest)
    shutil.copytree(tmp_dir, dest)
    logging.info(f"✔ Deployed version {base}")

    # 4) 记录到更新列表
    with open(VERSIONS_LIST, "a") as f:
        f.write(base + "\n")
    logging.info(f"✔ Appended to updates.txt: {base}")

    # 5) 标记完成
    done = proc.with_name(f"{base}.done.ply")
    proc.rename(done)

class Handler(FileSystemEventHandler):

    def on_created(self, evt):
        self._maybe_process(evt.src_path)
    def on_moved(self, evt):
        self._maybe_process(evt.dest_path)
    def _maybe_process(self, filepath):
        name = Path(filepath).name
        if not name.endswith(".ply") \
        or ".processing" in name \
        or ".done" in name:
            return
        logging.info(f"→ 触发处理:{name}")
        process_ply(Path(filepath))

def main():
    for d in (IN_DIR, TMP_ROOT, WWW_ROOT):
        d.mkdir(parents=True, exist_ok=True)
    # 清空旧的列表
    if VERSIONS_LIST.exists(): VERSIONS_LIST.unlink()

    # 初次扫描
    for ply in sorted(IN_DIR.glob("*.ply")):
        process_ply(ply)

    # 监听
    obs = Observer()
    obs.schedule(Handler(), str(IN_DIR), recursive=False)
    obs.start()
    logging.info(f"Watching {IN_DIR}")
    try:
        while True: time.sleep(POLL_INTERVAL)
    except KeyboardInterrupt:
        obs.stop()
    obs.join()

if __name__ == "__main__":
    main()

转换逻辑 process_ply() 包含:

  1. 重命名为 .processing.ply
  2. 调用 convert() 转换为 3D Tiles
  3. 部署到 www/pointcloud/<version>/
  4. 更新 updates.txt
  5. 重命名为 .done.ply

3.移动到GeoServer

如果需要服务化接口,也可以将 .ply 导入 PostgreSQL + PostGIS,并使用 GeoServer 提供 Web 服务。

4. 写入pgSQL中

使用 PDAL 或自定义工具,将点云写入 PostgreSQL 的 pointcloud 表结构中,便于空间索引与查询。

image-20250515160510195

5.Cesium加载对应的URL

将输出的子目录部署于GeoServer中通过以下 URL 访问 Cesium

image-20250515160607968

6.启动命令

cd ~/cesium-deepsea/SLAM/SVln2/svin_ws/
catkin_make
cd ~/cesium-deepsea/SLAM/SVln2
source svin_ws/devel/setup.bash
roslaunch okvis_ros svin_stereorig_v1_global.launch

cd ~/cesium-deepsea/SLAM/SVln2/svin_ws/datasets/Bus/
rosbag play bus_out_loop_w_cam_info.bag --clock -r 0.8

python3 convert_ply.py
# rosservice call /pose_graph_node/save_pointcloud

TODO

优化存储逻辑,目前存储内容导致不断扩张,需要优化存储逻辑

结合点云变动量计算是否保存(动态阈值)

补充完整代码以及说明文档


网站公告

今日签到

点亮在社区的每一天
去签到