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

ROS实现SLAM点云3D Tiles可视化

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

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

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

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

<think>根据用户的问题,用户意图是了解如何在ROS2中发布和订阅点云数据,并进行可视化。参考提供的引用内容,特别是引用[1]中关于ROS1的点云处理代码,以及引用[5]中关于3DSLAM的信息流,我们可以推断用户需要ROS2版本的示例。由于引用中并没有直接给出ROS2的代码,因此需要将ROS1的代码转换为ROS2的语法。 ROS2ROS1的主要区别在于节点初始化、订阅和发布的API变化,以及使用rclcpp库代替ros/ros.h。同时,可视化部分可以使用rqt_image_view(用于图像)或RViz(用于点云)。 步骤: 1. 创建一个ROS2节点,订阅点云话题。 2. 在回调函数中处理点云数据(这里简单示例,直接转发)。 3. 发布处理后的点云数据。 4. 使用RViz进行可视化。 注意:ROS2中处理点云通常使用pcl_ros(在ROS2中为pcl_conversions)和sensor_msgs/msg/PointCloud2。 由于用户要求可视化,我们还需要说明如何启动RViz并配置显示点云。 代码示例(ROS2 Foxy或Humble): ```cpp #include <rclcpp/rclcpp.hpp> #include <sensor_msgs/msg/point_cloud2.hpp> #include <pcl_conversions/pcl_conversions.h> #include <pcl/point_cloud.h> #include <pcl/point_types.h> using PointCloud2 = sensor_msgs::msg::PointCloud2; class PointCloudSubscriber : public rclcpp::Node { public: PointCloudSubscriber() : Node("point_cloud_subscriber") { // 创建订阅者,订阅名为"input"的点云话题 subscription_ = this->create_subscription<PointCloud2>( "input", 10, std::bind(&PointCloudSubscriber::topic_callback, this, std::placeholders::_1)); // 创建发布者,发布名为"output"的点云话题 publisher_ = this->create_publisher<PointCloud2>("output", 10); } private: void topic_callback(const PointCloud2::SharedPtr msg) const { // 这里可以添加点云处理代码,例如滤波、特征提取等 // 本例中,我们只是将接收到的点云直接转发 // 发布点云 publisher_->publish(*msg); } rclcpp::Subscription<PointCloud2>::SharedPtr subscription_; rclcpp::Publisher<PointCloud2>::SharedPtr publisher_; }; int main(int argc, char * argv[]) { rclcpp::init(argc, argv); rclcpp::spin(std::make_shared<PointCloudSubscriber>()); rclcpp::shutdown(); return 0; } ``` 可视化步骤: 1. 启动ROS2节点。 2. 启动RViz:`rviz2`。 3. 在RViz中添加一个`PointCloud2`显示类型。 4. 将`PointCloud2`显示的Topic设置为`/output`(或节点中发布的话题名称)。 注意事项: - 确保点云数据已经发布到`input`话题上,否则节点将接收不到数据。 - 在RViz中可能需要设置正确的Fixed Frame(通常是点云的坐标系,如`map`或`base_link`)。 相关问题: 1. 如何在ROS2中对点云进行滤波处理? 2. ROS2中如何将深度图像转换为点云? 3. 如何配置RViz以显示多种传感器数据?</think>### ROS2点云发布、订阅可视化教程 在ROS2中处理点云数据主要涉及以下步骤: #### 1. 创建ROS2节点(C++示例) ```cpp #include <rclcpp/rclcpp.hpp> #include <sensor_msgs/msg/point_cloud2.hpp> #include <pcl_conversions/pcl_conversions.h> #include <pcl/point_cloud.h> #include <pcl/point_types.h> using PointCloud2 = sensor_msgs::msg::PointCloud2; class PointCloudNode : public rclcpp::Node { public: PointCloudNode() : Node("point_cloud_node") { // 创建订阅者(订阅输入点云) subscription_ = this->create_subscription<PointCloud2>( "input_cloud", 10, std::bind(&PointCloudNode::cloud_callback, this, std::placeholders::_1)); // 创建发布者(发布处理后的点云) publisher_ = this->create_publisher<PointCloud2>("output_cloud", 10); } private: void cloud_callback(const PointCloud2::SharedPtr msg) { // 转换为PCL点云格式 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); pcl::fromROSMsg(*msg, *cloud); // 此处添加点云处理逻辑(示例:简单平移) for (auto& point : *cloud) { point.x += 0.1; } // 转换回ROS2消息格式 PointCloud2 output_msg; pcl::toROSMsg(*cloud, output_msg); output_msg.header = msg->header; // 发布处理后的点云 publisher_->publish(output_msg); } rclcpp::Subscription<PointCloud2>::SharedPtr subscription_; rclcpp::Publisher<PointCloud2>::SharedPtr publisher_; }; int main(int argc, char** argv) { rclcpp::init(argc, argv); rclcpp::spin(std::make_shared<PointCloudNode>()); rclcpp::shutdown(); return 0; } ``` #### 2. 配置CMakeLists.txt ```cmake find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) find_package(pcl_conversions REQUIRED) find_package(pcl_ros REQUIRED) add_executable(point_cloud_node src/point_cloud_node.cpp) target_include_directories(point_cloud_node PRIVATE ${PCL_INCLUDE_DIRS}) target_link_libraries(point_cloud_node ${rclcpp_LIBRARIES} ${sensor_msgs_LIBRARIES} ${pcl_conversions_LIBRARIES} ${PCL_LIBRARIES} ) install(TARGETS point_cloud_node DESTINATION lib/${PROJECT_NAME}) ``` #### 3. 可视化方法 1. **使用RViz2**: ```bash ros2 run rviz2 rviz2 ``` 添加`PointCloud2`显示类型,设置Topic为`/output_cloud` 2. **使用rqt**: ```bash ros2 run rqt_image_view rqt_image_view ``` (需先将点云转换为深度图像) 3. **PCL可视化**(开发调试): ```cpp #include <pcl/visualization/cloud_viewer.h> pcl::visualization::CloudViewer viewer("Cloud Viewer"); viewer.showCloud(cloud); while (!viewer.wasStopped()) {} ``` #### 4. 运行流程 1. 编译节点: ```bash colcon build --packages-select your_package source install/setup.bash ``` 2. 启动节点: ```bash ros2 run your_package point_cloud_node ``` 3. 发布测试点云: ```bash ros2 run pcl_ros pcd_to_pointcloud <path_to_pcd> --ros-args -r __ns:=/ -r input_cloud:=/output_cloud ``` 4. 在RViz2中查看可视化结果 [^1]: 引用[1]提供了ROS1的点云处理框架参考 [^5]: 引用[5]展示了3DSLAM系统中的点云处理流程 #### 注意事项 1. 确保安装ROS2 PCL支持: ```bash sudo apt install ros-<distro>-pcl-conversions ros-<distro>-pcl-ros ``` 2. 点云坐标系需正确设置(通过`header.frame_id`) 3. 大点云处理需考虑性能优化(如降采样)
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值