點雲有用的操作 


前言:最近在做點雲的工作,通過資料及其他網頁,總結一些比較常用且實用的操作,留給自己查看,同時也希望能給別人帶來方便。

 

1. 兩片點雲cloudA、cloudB,若在cloudB中找到cloudA的數據點,則從cloudB中刪除該點。

#include <pcl/point_cloud.h>        //點類型定義頭文件
#include <pcl/kdtree/kdtree_flann.h> //kdtree類定義頭文件

#include <iostream>
#include <vector>
#include <ctime>
const double eps = 1.0e-6;

int
main(int argc, char** argv)
{
    //srand(time(NULL));   //用系統時間初始化隨機種子
    //創建一個PointCloud<pcl::PointXYZ>
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloudA(new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloudB(new pcl::PointCloud<pcl::PointXYZ>);
    // 隨機點雲生成
    cloudA->width = 20;             //此處點雲數量
    cloudA->height = 1;                //表示點雲為無序點雲
    cloudA->points.resize(cloudA->width * cloudA->height);

    for (size_t i = 0; i < cloudA->points.size(); ++i)   //循環填充點雲數據
    {
        cloudA->points[i].x = i + 1;
        cloudA->points[i].y = i + 1;
        cloudA->points[i].z = i + 1;
    }

    cloudB->width = 20;             //此處點雲數量
    cloudB->height = 1;                //表示點雲為無序點雲
    cloudB->points.resize(cloudB->width * cloudB->height);
    for (size_t i = 0; i < cloudB->points.size(); ++i)   //循環填充點雲數據
    {
        cloudB->points[i].x = i + 8;
        cloudB->points[i].y = i + 8;
        cloudB->points[i].z = i + 8;
    }
    //cloudBackup->points = cloud->points;
    //創建KdTreeFLANN對象,並把創建的點雲設置為輸入,創建一個searchPoint變量作為查詢點
    pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;

    pcl::PointXYZ searchPoint;
    int K = 1;
    std::vector<int> pointIdxNKNSearch(K);      //存儲查詢點近鄰索引
    std::vector<float> pointNKNSquaredDistance(K); //存儲近鄰點對應距離平方
    std::vector<pcl::PointXYZ> DeleteData;
    int num = 0;
    for (auto iterA = cloudA->begin(); iterA != cloudA->end(); iterA++)
    {
        searchPoint.x = iterA->x;
        searchPoint.y = iterA->y;
        searchPoint.z = iterA->z;
        kdtree.setInputCloud(cloudB);    //在cloudB中找到對應點后,在cloudB中直接刪除該點
        num = kdtree.nearestKSearch(searchPoint, K, pointIdxNKNSearch, pointNKNSquaredDistance);
        if (num > 0)
        {
            if (sqrt(pointNKNSquaredDistance[0])<eps)
            {
                auto iterB = cloudB->begin() + pointIdxNKNSearch[0];
                cloudB->erase(iterB);
                DeleteData.push_back(searchPoint);
                if (cloudB->size()==0)
                {
                    break;
                }
                searchPoint.x = 0;
                searchPoint.y = 0;
                searchPoint.z = 0;
                num = 0;
                pointIdxNKNSearch.clear();
                pointNKNSquaredDistance.clear();
            }
        }
        
    }
    
    for (auto iter = DeleteData.begin(); iter != DeleteData.end(); iter++)
    {
        std::cout << iter->x << " " << iter->y << " " << iter->z << std::endl;
    }

    system("pause");
    return 0;
}

 

2.幾種常用的操作

(1)保存點雲數據

//普通格式ASSIC(占用內存較大)
pcl::PCDWriter writer;
writer.write(s_pcd,laserCloudIn);

//bin格式(占用內存較小)
pcl::io::savePCDFileBinary(s_pcd, *cloud);

(2)查找點雲在X、Y、Z軸的極值

pcl::PointXYZ minPt, maxPt;
pcl::getMinMax3D (*cloud, minPt, maxPt);

(3)知道要保存點的索引,從原點雲中拷貝點到新點雲

pcl::PointCloud::Ptr cloudOut(new pcl::PointCloud);
std::vector indexs = { 1, 2, 5 };
pcl::copyPointCloud(*cloud, indexs, *cloudOut);

(4)從點雲里刪除和添加點

pcl::PointCloud::iterator index = cloud->begin();
cloud->erase(index);//刪除第一個
index = cloud->begin() + 5;
cloud->erase(index);//刪除第5個
pcl::PointXYZ point = { 1, 1, 1 };
//在索引號為5的位置上插入一點,之后的所有點后移一位
cloud->insert(cloud->begin() + 5, point);
cloud->push_back(point);//從點雲最后面插入一點

(5)對點雲進行全局或局部變換

//全部
pcl::transformPointCloud(*cloud,*transform_cloud1,transform_1);
        
//局部
//第一個參數為輸入,第二個參數為輸入點雲中部分點集索引,第三個為存儲對象,第四個是變換矩陣。
pcl::transformPointCloud(*cloud,pcl::PointIndices indices,*transform_cloud1,matrix); 

(6)鏈接兩個點雲字段(兩點雲大小必須相同)

pcl::PointCloud::Ptr cloud_with_nomal (new pcl::PointCloud);
pcl::concatenateFields(*cloud,*cloud_normals,*cloud_with_nomal);

(7)從點雲中刪除無效點

vector indices;
pcl::removeNaNFromPointCloud(*cloud,*output,indices);

(8)計算質心

Eigen::Vector4f centroid;//質心
pcl::compute3DCentroid(*cloud_smoothed,centroid); //估計質心的坐標

(9)計算點雲的法向量

pcl::NormalEstimation ne;
pcl::PointCloud::Ptr pcNormal(new pcl::PointCloud);  
pcl::search::KdTree::Ptr tree(new pcl::search::KdTree);
tree->setInputCloud(inCloud);  
ne.setInputCloud(inCloud);  
ne.setSearchMethod(tree);  
ne.setKSearch(50);  
//ne->setRadiusSearch (0.03);   
ne.compute(*pcNormal);

(10)提取點雲的邊界

pcl::PointCloud boundaries; //保存邊界估計結果pcl::BoundaryEstimation boundEst; //定義一個進行邊界特征估計的對象
pcl::NormalEstimation normEst; //定義一個法線估計的對象
pcl::PointCloud::Ptr normals(new pcl::PointCloud); //保存法線估計的結果
pcl::PointCloud::Ptr cloud_boundary (new pcl::PointCloud); 
normEst.setInputCloud(pcl::PointCloud::Ptr(cloud)); 
normEst.setRadiusSearch(reforn); //設置法線估計的半徑
normEst.compute(*normals); //將法線估計結果保存至normals

 
boundEst.setInputCloud(cloud); //設置輸入的點雲
boundEst.setInputNormals(normals); //設置邊界估計的法線,因為邊界估計依賴於法線
boundEst.setRadiusSearch(re); //設置邊界估計所需要的半徑
boundEst.setAngleThreshold(M_PI/4); //邊界估計時的角度閾值
boundEst.setSearchMethod(pcl::search::KdTree::Ptr (new pcl::search::KdTree)); //設置搜索方式KdTree
boundEst.compute(boundaries); //將邊界估計結果保存在boundaries

(11)k近鄰和半徑搜索

pcl::KdTreeFLANNkdtree; //創建kdtree搜索對象
kdtree.setInputCloud(cloud);           //載入點雲
pcl::PointXYZ searchPoint;              //設置查詢點並賦隨機值
//K近鄰搜索
int K = 10;                             //搜索最近鄰的點數
vectorpointIdxNKNSearch(K);        //存放最近鄰點的索引
vectorpointNKNSquaredDistance(K);//對應的距離平方
kdtree.nearestKSearch(searchPoint, K, pointIdxNKNSearch, pointNKNSquaredDistance)
//半徑內搜索
std::vector pointIdxRadiusSearch;
std::vector pointRadiusSquaredDistance;
float radius; //定義搜索半徑
kdtree.radiusSearch(searchPoint, radius, pointIdxRadiusSearch, pointRadiusSquaredDistance);

(12)添加新的點雲類

//有自定義點雲類型時要加入該頭文件才能使用PCL庫模板函數
#include   
//運用相應的函數需加入以下相應頭文件
//如:直通濾波器
#include 

//定義一個新的點雲類
struct PointXYZIR
{
  PCL_ADD_POINT4D
  float intensity;
  uint16_t ring;                   ///< laser ring number
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW  //確保new操作符對齊
} EIGEN_ALIGN16; //強制SSE對齊

POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIR, (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(uint16_t, ring, ring))

 

3. 幾種點雲常用的濾波器

(1)直通濾波器

// 創建濾波器對象
pcl::PassThrough<pcl::PointXYZ> pass;
pass.setInputCloud (cloud);
pass.setFilterFieldName ("z");
pass.setFilterLimits (0.0, 1.0);
//pass.setFilterLimitsNegative (true);
pass.filter (*cloud_filtered);

(2)VoxelGrid濾波器

創建三維體素柵格,將體素柵格內所有點的重心代替體素中其他點,實現下采樣。

// 創建濾波器對象
pcl::VoxelGrid<pcl::PointXYZ> sor;
sor.setInputCloud(cloud);
sor.setLeafSize(0.01f, 0.01f, 0.01f);
sor.filter(*cloud_filtered);            

(3)StatisticalOutlireRemoval濾波器

對每一個點的近鄰進行一個統計分析,計算點到近鄰點的距離,計算所有近鄰點的平均距離,平均距離在標准范圍之外的點被視為離群點

// 創建濾波器對象
pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
sor.setInputCloud (cloud);
sor.setMeanK (50);
sor.setStddevMulThresh (1.0);
sor.filter (*cloud_filtered);

(4)使用參數化模型投影點雲

基於對模型的結構和尺寸等信息,選擇特殊模型,如:球等,設置參數進行濾波。

首先,填充ModelCoefficients的值,該例中使用X-Y平面

//創建一個系數為(0,0,1,0)的平面
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
coefficients->values.resize(4);
coefficients->values[0] = coefficients->values[1] = 0;
coefficients->values[2] = 1.0;
coefficients->values[3] = 0;

然后,創建ProjectInliers對象,使用ModelCoefficients作為投影對象的模型參數

//創建濾波器對象
pcl::ProjectInliers<pcl::PointXYZ>proj;
proj.setModelType(pcl::SACMODEL_PLANE);
proj.setInputCloud(cloud);
proj.setModelCoefficients(coefficients);
proj.filter(*cloud_projected);

(5)ExtractIndices濾波器

基於某一分割算法提取點雲的一個子集

首先,使用VoxelGrid濾波器對數據下采樣,加快處理速度

// 創建濾波器對象:使用葉大小為1cm的下采樣
pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
sor.setInputCloud(cloud_blob);
sor.setLeafSize(0.01f, 0.01f, 0.01f);
sor.filter(*cloud_filtered_blob);

接着,參數化分割

然后,設置extraction filter實際參數

pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
pcl::PointIndices::Ptr inliers(new pcl::PointIndices());
// 創建分割對象
pcl::SACSegmentation<pcl::PointXYZ> seg;
// 可選
seg.setOptimizeCoefficients(true);
// 必選
seg.setModelType(pcl::SACMODEL_PLANE);
seg.setMethodType(pcl::SAC_RANSAC);
seg.setMaxIterations(1000);
seg.setDistanceThreshold(0.01);
// 創建濾波器對象
pcl::ExtractIndices<pcl::PointXYZ> extract;
int i = 0, nr_points = (int)cloud_filtered->points.size();
// 當還有30%原始點雲數據時
while (cloud_filtered->points.size() > 0.3 * nr_points)
{
    // 從余下的點雲中分割最大平面組成部分
    seg.setInputCloud(cloud_filtered);
    seg.segment(*inliers, *coefficients);
    if (inliers->indices.size() == 0)
    {
        std::cerr << "Could not estimate a planar model for the given dataset." << std::endl;
        break;
    }
    // 分離內層
    extract.setInputCloud(cloud_filtered);
    extract.setIndices(inliers);
    extract.setNegative(false);
    extract.filter(*cloud_p);
    std::cerr << "PointCloud representing the planar component: " << cloud_p->width * cloud_p->height << " data points." << std::endl;
    std::stringstream ss;
    ss << "table_scene_lms400_plane_" << i << ".pcd";
    writer.write<pcl::PointXYZ>(ss.str(), *cloud_p, false);
    // 創建濾波器對象
    extract.setNegative(true);
    extract.filter(*cloud_f);
    cloud_filtered.swap(cloud_f);
    i++;
}

 需要將sensor_msgs::PointCloud2::Ptr改為pcl::PCLPointCloud2::Ptr;pcl::fromROSMsg()改為pcl::fromPCLPointCloud2();

 (6)ConditionalRemoval或RadiusOutlierRemoval類

ConditionalRemoval濾波器可以刪除設定的一個或多個條件指標的所有數據點;

首先,創建條件限定對象,為限定對象添加比較算子,創建濾波器並用條件定義對象初始化,

// 創建環境
pcl::ConditionAnd<pcl::PointXYZ>::Ptr range_cond(new
            pcl::ConditionAnd<pcl::PointXYZ>());
range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr(new
            pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::GT, 0.0)));
range_cond->addComparison(pcl::FieldComparison<pcl::PointXYZ>::ConstPtr(new
            pcl::FieldComparison<pcl::PointXYZ>("z", pcl::ComparisonOps::LT, 0.8)));
// 創建濾波器
pcl::ConditionalRemoval<pcl::PointXYZ> condrem(range_cond);
condrem.setInputCloud(cloud);
condrem.setKeepOrganized(true);
// 應用濾波
condrem.filter(*cloud_filtered);

然后,RadiusOutlinerRemoval濾波器刪除搜索半徑內不滿足設定的近鄰點數,可用於移除離群點。

pcl::RadiusOutlierRemoval<pcl::PointXYZ> outrem;
// 創建濾波器
outrem.setInputCloud(cloud);
outrem.setRadiusSearch(0.8);  // 設置搜索半徑
outrem.setMinNeighborsInRadius(2);   // 設置查詢點的近鄰點數
// 應用濾波器
outrem.filter(*cloud_filtered);

(7)CropHull濾波器

獲取2D封閉多邊形內部或者外部的點雲

首先,設置2D封閉多邊形頂點;

然后,使用ConvexHull類構造2D凸包;

最后,創建Crophull對象,濾波獲取凸包范圍內的點雲。

pcl::PointCloud<pcl::PointXYZ>::Ptr boundingbox_ptr(new pcl::PointCloud<pcl::PointXYZ>);
boundingbox_ptr->push_back(pcl::PointXYZ(0.1, 0.1, 0));
boundingbox_ptr->push_back(pcl::PointXYZ(0.1, -0.1, 0));
boundingbox_ptr->push_back(pcl::PointXYZ(-0.1, 0.1, 0));
boundingbox_ptr->push_back(pcl::PointXYZ(-0.1, -0.1, 0));
boundingbox_ptr->push_back(pcl::PointXYZ(0.15, 0.1, 0));

pcl::ConvexHull<pcl::PointXYZ> hull;
hull.setInputCloud(boundingbox_ptr);
hull.setDimension(2);
std::vector<pcl::Vertices> polygons;
pcl::PointCloud<pcl::PointXYZ>::Ptr surface_hull(new pcl::PointCloud<pcl::PointXYZ>);
hull.reconstruct(*surface_hull, polygons);

pcl::PointCloud<pcl::PointXYZ>::Ptr objects(new pcl::PointCloud<pcl::PointXYZ>);
pcl::CropHull<pcl::PointXYZ> bb_filter;
bb_filter.setDim(2);
bb_filter.setInputCloud(cloud);
bb_filter.setHullIndices(polygons);
bb_filter.setHullCloud(surface_hull);
bb_filter.filter(*objects);

 

 

參考:

https://www.jianshu.com/p/57bbad9c39d6

https://blog.csdn.net/zhan_zhan1/article/details/103991733?utm_medium=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-2.channel_param&depth_1-utm_source=distribute.pc_relevant.none-task-blog-BlogCommendFromMachineLearnPai2-2.channel_param

https://www.it610.com/article/1282154616984715264.htm


免責聲明!

本站轉載的文章為個人學習借鑒使用,本站對版權不負任何法律責任。如果侵犯了您的隱私權益,請聯系本站郵箱yoyou2525@163.com刪除。



 
粵ICP備18138465號   © 2018-2025 CODEPRJ.COM