PCL 将点云投影到圆柱

目录

一、概述

1.1原理

1.2实现步骤

1.3应用场景

二、代码实现

2.1关键函数

2.1.1 计算点云投影到球面

2.1.2 可视化原始点云与投影点云

2.2完整代码

三、实现效果


PCL点云算法汇总及实战案例汇总的目录地址链接:

PCL点云算法与项目实战案例汇总(长期更新)


一、概述

1.1原理

        本次实现基于球面模型的投影原理。点云数据中的每个点会根据指定的球面方程(由球心和半径确定)重新计算其坐标,并投影到球面表面。球面投影的公式如下:

        对于一个点 (x, y, z),其距离原点的距离为 d,球面方程 x² + y² + z² = r²。通过调整该点在球面上的位置,将其投影到指定球面的表面,投影点坐标计算为:

其中 (x_0, y_0, z_0) 是球心的坐标,r 是球的半径,d 是原始点到原点的距离。

1.2实现步骤

  1. 读取点云数据。
  2. 定义球面的中心和半径。
  3. 计算每个点投影到球面上的新坐标。
  4. 将投影后的点云保存,并可视化原始点云与投影后的点云。

1.3应用场景

  1. 3D建模:在3D建模或图像处理中,通过将点云投影到球面,处理具有球体形状的物体。
  2. 地形重建:对于具有球面特征的地形数据,可以投影点云进行曲面拟合分析。
  3. 几何分析:通过球面投影,可以对复杂物体的几何特性进行简化和分析。

二、代码实现

2.1关键函数

2.1.1 计算点云投影到球面

// 计算点云中每个点投影到球面上的坐标
void projectPointCloudToSphere(
    pcl::PointCloud<PointT>::Ptr cloud,
    pcl::PointCloud<PointT>::Ptr cloud_projected,
    float centerX, float centerY, float centerZ, float radius)
{
    for (size_t i = 0; i < cloud->points.size(); ++i)
    {
        PointT point;
        float distance = cloud->points[i].getVector3fMap().norm();  // 计算点与原点的距离
        // 计算投影到球面的坐标
        point.x = (cloud->points[i].x) * radius / distance + centerX;
        point.y = (cloud->points[i].y) * radius / distance + centerY;
        point.z = (cloud->points[i].z) * radius / distance + centerZ;
        point.rgb = cloud->points[i].rgb;  // 保留颜色信息
        cloud_projected->points.push_back(point);
    }
    cloud_projected->width = cloud->width;
    cloud_projected->height = cloud->height;
    cloud_projected->is_dense = cloud->is_dense;
}

2.1.2 可视化原始点云与投影点云

#include <pcl/visualization/pcl_visualizer.h>

// 可视化原始点云和投影后的点云
void visualizePointClouds(
    pcl::PointCloud<PointT>::Ptr cloud,
    pcl::PointCloud<PointT>::Ptr projected_cloud)
{
    // 创建一个可视化窗口,分别显示原始点云和投影后的点云
    pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("Point Cloud Visualization"));
    
    // 设置视口1,显示原始点云
    int vp_1;
    viewer->createViewPort(0.0, 0.0, 0.5, 1.0, vp_1);
    viewer->setBackgroundColor(1.0, 1.0, 1.0, vp_1);  // 白色背景
    viewer->addText("Original PointCloud", 10, 10, "vp1_text", vp_1);
    pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb(cloud);
    viewer->addPointCloud(cloud, rgb, "original_cloud", vp_1);
    viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "original_cloud", vp_1);

    // 设置视口2,显示投影后的点云
    int vp_2;
    viewer->createViewPort(0.5, 0.0, 1.0, 1.0, vp_2);
    viewer->setBackgroundColor(0.98, 0.98, 0.98, vp_2);  // 浅灰色背景
    viewer->addText("Projected PointCloud", 10, 10, "vp2_text", vp_2);
    pcl::visualization::PointCloudColorHandlerRGBField<PointT> rgb_projected(projected_cloud);
    viewer->addPointCloud(projected_cloud, rgb_projected, "projected_cloud", vp_2);
    viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "projected_cloud", vp_2);

    while (!viewer->wasStopped())
    {
        viewer->spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }
}

2.2完整代码

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <boost/thread/thread.hpp>

struct sphere
{
    float centerX;
    float centerY;
    float centerZ;
    float radius;
};

using PointT = pcl::PointXYZRGB;

// 计算点云中每个点投影到球面上的坐标
void projectPointCloudToSphere(
    pcl::PointCloud<PointT>::Ptr cloud,
    pcl::PointCloud<PointT>::Ptr cloud_projected,
    float centerX, float centerY, float centerZ, float radius)
{
    for (size_t i = 0; i < cloud->points.size(); ++i)
    {
        PointT point;
        float distance = cloud->points[i].getVector3fMap().norm();  // 计算点与原点的距离
        // 计算投影到球面的坐标
        point.x = (cloud->points[i].x) * radius / distance + centerX;
        point.y = (cloud->points[i].y) * radius / distance + centerY;
        point.z = (cloud->points[i].z) * radius / distance + centerZ;
        point.rgb = cloud->points[i].rgb;  // 保留颜色信息
        cloud_projected->points.push_back(point);
    }
    cloud_projected->width = cloud->width;
    cloud_projected->height = cloud->height;
    cloud_projected->is_dense = cloud->is_dense;
}


// 可视化原始点云和投影后的点云
void visualizePointClouds(
    pcl::PointCloud<PointT>::Ptr cloud,
    pcl::PointCloud<PointT>::Ptr projected_cloud)
{
    // 创建一个可视化窗口,分别显示原始点云和投影后的点云
    pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("Point Cloud Visualization"));

    // 设置视口1,显示原始点云
    int vp_1;
    viewer->createViewPort(0.0, 0.0, 0.5, 1.0, vp_1);
    viewer->setBackgroundColor(1.0, 1.0, 1.0, vp_1);  // 白色背景
    viewer->addText("Original PointCloud", 10, 10, "vp1_text", vp_1);
    pcl::visualization::PointCloudColorHandlerCustom<PointT> cloud_color(cloud, 255, 0, 0);  // 原始点云为红色
    viewer->addPointCloud(cloud, cloud_color, "original_cloud", vp_1);
    viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "original_cloud", vp_1);

    // 设置视口2,显示投影后的点云
    int vp_2;
    viewer->createViewPort(0.5, 0.0, 1.0, 1.0, vp_2);
    viewer->setBackgroundColor(0.98, 0.98, 0.98, vp_2);  // 浅灰色背景
    viewer->addText("Projected PointCloud", 10, 10, "vp2_text", vp_2);
    pcl::visualization::PointCloudColorHandlerCustom<PointT> projected_color(projected_cloud, 0, 255, 0);  // 投影后的点云为绿色
    viewer->addPointCloud(projected_cloud, projected_color, "projected_cloud", vp_2);
    viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 2, "projected_cloud", vp_2);

    // 进入渲染循环
    while (!viewer->wasStopped())
    {
        viewer->spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }
}


int main(int argc, char** argv)
{
    // ---------------------------加载点云数据----------------------------------
    pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
    if (pcl::io::loadPCDFile("侍女.pcd", *cloud) == -1) {
        PCL_ERROR("Could not read pcd file!\n");
        return -1;
    }
    std::cout << "投影前点的个数为: " << cloud->points.size() << std::endl;

    // -----------------------给定待投影的球面系数------------------------------
    sphere SP;
    SP.centerX = 0.1181;
    SP.centerY = -0.1363;
    SP.centerZ = -0.1567;
    SP.radius = 5.1674;

    // ------------------------计算投影后点的坐标-------------------------------
    pcl::PointCloud<PointT>::Ptr cloud_projected(new pcl::PointCloud<PointT>);
    projectPointCloudToSphere(cloud, cloud_projected, SP.centerX, SP.centerY, SP.centerZ, SP.radius);

    std::cout << "投影后点的个数为: " << cloud_projected->points.size() << std::endl;
    //pcl::io::savePCDFileBinary("cloud_projected.pcd", *cloud_projected);

    // --------------------------可视化投影结果----------------------------------
    visualizePointClouds(cloud, cloud_projected);

    return 0;
}

三、实现效果

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值