随着激光雷达,RGBD相机等3D传感器在机器人,无人驾驶领域的广泛应用。
针对三维点云数据的研究也逐渐从低层次几何特征提取( PFH, FPFH,VFH等)向高层次语义理解过渡(点云识别,语义分割)。与图像感知领域深度学习几乎一统天下不同,针对无序点云数据的深度学习方法研究则进展缓慢。分析其背后的原因,不外乎三个方面:

1.点云具有无序性。受采集设备以及坐标系影响,同一个物体使用不同的设备或者位置扫描,三维点的排列顺序千差万别,这样的数据很难直接通过End2End的模型处理。

2.点云具有稀疏性。在机器人和自动驾驶的场景中,激光雷达的采样点覆盖相对于场景的尺度来讲,具有很强的稀疏性。在KITTI数据集中,如果把原始的激光雷达点云投影到对应的彩色图像上,大概只有3%的像素才有对应的雷达点。这种极强的稀疏性让基于点云的高层语义感知变得尤其困难。

3.点云信息量有限。点云的数据结构就是一些三维空间的点坐标构成的点集,本质是对三维世界几何形状的低分辨率重采样,因此只能提供片面的几何信息。在这里插入图片描述
https://robotica.unileon.es/index.php?title=PCL/OpenNI_tutorial_4:3D_object_recognition(descriptors)

在这里插入图片描述

数据与特征决定了机器学习的上限,
模型/算法/参数只是来逼近这个上限。

0: 分类方式

按照特征的物理属性,可以将特征分为:几何域,强度域。

按照特征的空间尺度,可以分为:单点特征,局部特征,全局特征。

1:传统特征

在点云分类任务中,可直接利用特征向量训练SVM或者多层感知机来进行分类,而在以点为单位的点云分割或者分块任务中,需要结合每一点的局部特征和全局特征进行特征融合和处理,实现逐点的分类。

单点特征

主要有:三维坐标(X, Y, Z), 回波强度 Intensity, 法线 (Nx,Ny,Nz),主曲率(PCx, PCy, PCz, 及两个特征值 PC1, PC2)

局部特征

(一)几何域
局部特征常见的有各种几何特征描述子:PFH,FPFH,SHOT,C-SHOT,RSD,3D形状描述子等。

点特征直方图(Point Feature Histograms)
点特征直方图(PFH)表示法是基于点与其k邻域之间的关系以及它们的估计法线,简言之,它考虑估计法线方向之间所有的相互作用,试图捕获最好的样本表面变化情况,以描述样本的几何特征。

#include <pcl/point_types.h>                  //点类型头文件
#include <pcl/features/pfh.h>                 //pfh特征估计类头文件
...//其他相关操作
pcl::PointCloud<pcl::PointXYZ>::Ptrcloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::Normal>::Ptrnormals(new pcl::PointCloud<pcl::Normal>());
...//打开点云文件估计法线等
//创建PFH估计对象pfh,并将输入点云数据集cloud和法线normals传递给它
pcl::PFHEstimation<pcl::PointXYZ,pcl::Normal,pcl::PFHSignature125> pfh;
pfh.setInputCloud(cloud);
pfh.setInputNormals(normals);
//如果点云是类型为PointNormal,则执行pfh.setInputNormals (cloud);
//创建一个空的kd树表示法,并把它传递给PFH估计对象。
//基于已给的输入数据集,建立kdtree
pcl::KdTreeFLANN<pcl::PointXYZ>::Ptrtree(new pcl::KdTreeFLANN<pcl::PointXYZ>());
pfh.setSearchMethod(tree);
//输出数据集
pcl::PointCloud<pcl::PFHSignature125>::Ptrpfhs(new pcl::PointCloud<pcl::PFHSignature125>());
//使用半径在5厘米范围内的所有邻元素。
//注意:此处使用的半径必须要大于估计表面法线时使用的半径!!!
pfh.setRadiusSearch(0.05);
//计算pfh特征值
pfh.compute(*pfhs);
// pfhs->points.size ()应该与input cloud->points.size ()有相同的大小,即每个点都有一个pfh特征向量

(二)强度域

强度梯度(IGx, IGy, IGz):

全局特征

(一)几何域

常见的几何域全局特征有:
PFH:
VFH:Viewpoint Feature Histogram
CVFH:在VFH基础上解决了点云残缺的问题。

发展历程:PFH、 FPHF、VFH

PFH点特征的描述子一般是基于点坐标、法向量、曲率来描述某个点周围的几何特征。用点特征描述子不能提供特征之间的关系,减少了全局特征信息。因此诞生了一直基于直方图的特征描述子:PFH–point feature histogram(点特征直方图)。

PFH通过参数化查询点和紧邻点之间的空间差异,形成了一个多维直方图对点的近邻进行几何描述,直方图提供的信息对于点云具有平移旋转不变性,对采样密度和噪声点具有稳健性。PFH是基于点与其邻近之间的关系以及它们的估计法线,也即是它考虑估计法线之间的相互关系,来描述几何特征。

统计点对直接的关系,所有的四元组将会以某种统计的方式放进直方图中
在这里插入图片描述
通过点对数据,转为四组值,
把两点和它们法线相关的12个参数(xyz坐标值和法线信息)减少到4个。
如下方式:
在这里插入图片描述

#include <pcl/features/vfh.h>
#include <pcl/features/normal_3d.h>//法线特征

------------------------------------------------------
// =====计算法线========创建法线估计类====================================
  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
  ne.setInputCloud (cloud_ptr);

// 添加搜索算法 kdtree search  最近的几个点 估计平面 协方差矩阵PCA分解 求解法线
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
  ne.setSearchMethod (tree);//设置近邻搜索算法 
  // 输出点云 带有法线描述
  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ptr (new pcl::PointCloud<pcl::Normal>);
  pcl::PointCloud<pcl::Normal>& cloud_normals = *cloud_normals_ptr;
  // Use all neighbors in a sphere of radius 3cm
  ne.setRadiusSearch (0.03);//半价内搜索临近点 3cm
  // 计算表面法线特征
  ne.compute (cloud_normals);


//=======创建VFH估计对象vfh,并把输入数据集cloud和法线normal传递给它================
  pcl::VFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::VFHSignature308> vfh;
  //pcl::PFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::PFHSignature125> pfh;// phf特征估计其器
  //pcl::FPFHEstimation<pcl::PointXYZ,pcl::Normal,pcl::FPFHSignature33> fpfh;// fphf特征估计其器
  // pcl::FPFHEstimationOMP<pcl::PointXYZ,pcl::Normal,pcl::FPFHSignature33> fpfh;//多核加速
  vfh.setInputCloud (cloud_ptr);
  vfh.setInputNormals (cloud_normals_ptr);
  //如果点云是PointNormal类型,则执行vfh.setInputNormals (cloud);
  //创建一个空的kd树对象,并把它传递给FPFH估计对象。
  //基于已知的输入数据集,建立kdtree
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree2 (new pcl::search::KdTree<pcl::PointXYZ> ());
  //pcl::KdTreeFLANN<pcl::PointXYZ>::Ptr tree2 (new pcl::KdTreeFLANN<pcl::PointXYZ> ()); //-- older call for PCL 1.5-
  vfh.setSearchMethod (tree2);//设置近邻搜索算法 
  //输出数据集
  //pcl::PointCloud<pcl::PFHSignature125>::Ptr pfh_fe_ptr (new pcl::PointCloud<pcl::PFHSignature125> ());//phf特征
  //pcl::PointCloud<pcl::FPFHSignature33>::Ptr fpfh_fe_ptr (new pcl::PointCloud<pcl::FPFHSignature33>());//fphf特征
  pcl::PointCloud<pcl::VFHSignature308>::Ptr vfh_fe_ptr (new pcl::PointCloud<pcl::VFHSignature308> ());//vhf特征
  //使用半径在5厘米范围内的所有邻元素。
  //注意:此处使用的半径必须要大于估计表面法线时使用的半径!!!
  //fpfh.setRadiusSearch (0.05);
  //计算pfh特征值
  vfh.compute (*vfh_fe_ptr);

三维不变矩:矩特征主要表征了图像区域的几何特征,又称为几何矩, 由于其具有旋转、平移、尺度等特性的不变特征,所以又称其为不变矩。但要注意,不变矩对点云密度十分敏感!

常用的特征描述算法有:
法线和曲率计算 normal_3d_feature 、
特征值分析、
PFH 点特征直方图描述子 nk2、
FPFH 快速点特征直方图描述子 FPFH是PFH的简化形式 nk、
3D Shape Context、 文理特征
Spin Image
VFH视点特征直方图(Viewpoint Feature Histogram)
NARF关键点 pcl::NarfKeypoint narf特征 pcl::NarfDescriptor
RoPs特征(Rotational Projection Statistics)

https://github.com/Ewenwan/MVision/tree/master/PCL_APP

例如:利用VFH+SVM训练模型
VFH特征提取

#include <pcl/features/vfh.h>
#include <pcl/features/normal_3d.h>//法线特征
 
pcl::PointCloud<pcl::VFHSignature308> GetVFHFeature(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr)
{
	pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
	ne.setInputCloud(cloud_ptr);
	pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>());
	ne.setSearchMethod(tree);//设置近邻搜索算法 
	pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ptr(new pcl::PointCloud<pcl::Normal>);
	pcl::PointCloud<pcl::Normal>& cloud_normals = *cloud_normals_ptr;
	ne.setKSearch(40);  // 临近值50
	// 计算表面法线特征
	ne.compute(cloud_normals);
 
	pcl::VFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::VFHSignature308> vfh;
	vfh.setInputCloud(cloud_ptr);
	vfh.setInputNormals(cloud_normals_ptr);
	pcl::search::KdTree<pcl::PointXYZ>::Ptr tree2(new pcl::search::KdTree<pcl::PointXYZ>());
	vfh.setSearchMethod(tree2);//设置近邻搜索算法 
	pcl::PointCloud<pcl::VFHSignature308>::Ptr vfh_fe_ptr(new pcl::PointCloud<pcl::VFHSignature308>());//vhf特征
	vfh.compute(*vfh_fe_ptr);
 
	return *vfh_fe_ptr;
}


#include<pcl/visualization/pcl_plotter.h>  // plotter
  
  int main()
{
	pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
	pcl::io::loadPCDFile("./banana_train/banana_1.pcd", *cloud);
	pcl::PointCloud<pcl::FPFHSignature33>::Ptr fphf_ (new pcl::PointCloud<pcl::FPFHSignature33>());;
	*fphf_ = Get_FPFH_Feature(cloud);
	pcl::visualization::PCLPlotter *plotter = new pcl::visualization::PCLPlotter("My Plotter");
	//设置特性
	plotter->setShowLegend(true);
	std::cout << pcl::getFieldsList<pcl::FPFHSignature33>(*fphf_);
 
	//显示
	plotter->addFeatureHistogram<pcl::FPFHSignature33>(*fphf_, "fpfh", 0);
	plotter->spin();
	plotter->clearPlots();
	system("pause");
	return 0;
}

特征可视化如下:
在这里插入图片描述
在这里插入图片描述

SVM 特征分类

SVM
1.两分类的时候标签定义为-11
2.多分类的时候标签定义从1开始,用到测试时是int index = model->detect();
3.两分类的时候可生成txt或者xml文件,多分类只能用xml

选择核函数非常重要:

enum KernelTypes {
    /** Returned by SVM::getKernelType in case when custom kernel has been set */
    CUSTOM=-1,
    //线性核
    LINEAR=0,
    //多项式核
    POLY=1,
    //径向基核(高斯核)
    RBF=2,
    //sigmoid核
    SIGMOID=3,
    //指数核,与高斯核类似
    CHI2=4,
    //直方图核
    INTER=5
};

VFH数据提取代码
对扩展的FPFH分量来说,默认的VFH的实现使用45个子区间进行统计,
而对于视点分量要使用128个子区间进行统计,这样VFH就由一共308个浮点数组成阵列


void
getPointCloud::getTrainingData(std::vector <cv::Mat>& _trainingData,
                               std::vector <cv::Mat>& _trainingLabels){
    float minX,minY,minZ=1000.0;
    float maxX,maxY,maxZ=0.0;
    pcl::VoxelGrid<pcl::PointXYZ> vg;
    cv::Mat label = cv::Mat::zeros(1,1,CV_32FC1);
    for(size_t fileIdx=0; fileIdx<DataFiles.size();fileIdx++){
        std::vector<std::string> files = std::vector<std::string>();
        pcl::PointXYZ minPt, maxPt;
        int skip=0;
        getdir(DataFiles[fileIdx]+"/",files);
            cv::Mat trainingData;
            cv::Mat trainingLabels;
        for (unsigned int i = 0;i < files.size();i++) {
//                 remove this after testing classifier training
//            if(skip > 5){break;}
//            skip++;

            if(files[i] == "."  || files[i] == ".."){
                ROS_INFO(" . or .. files ignored");
            }
            else{
                std::cout << " [ processing ] " << files[i];

                cloud = loadCloud(DataFiles[fileIdx]+"/"+files[i]);
                //-- voxelization of the cloud --------//
                vg.setInputCloud (cloud);
                vg.setLeafSize (0.005f, 0.005f, 0.005f);
                vg.filter (*cloud);
                //-- Getting the descriptors ----------//
                pc.cloudinput(cloud);
                VFH_descriptor = pc.getDescriptor();
                cv::Mat _descriptor = cv::Mat::zeros(1,306,CV_32FC1);

                for(size_t i=0;i<306;i++){
                    _descriptor.at<float>(0,i)=(float)VFH_descriptor->points[0].histogram[i];
                }
                //-------------------------------------//
                trainingData.push_back(_descriptor);
                if(DataFiles[fileIdx] == (PCD_BASE_PATH+CLASSIFIER_NAME)){
                    label.at<float>(0,0)=1.0;
                    trainingLabels.push_back(label);
                    std::cout << " [label] 1.0";
                }
                else{
                    label.at<float>(0,0)= -1.0;
                    trainingLabels.push_back(label);
                    std::cout << " [label] -1.0";
                }
                std::cout << std::endl;

            }
        }
        _trainingData.push_back(trainingData);
        _trainingLabels.push_back(trainingLabels);
    }
}

可以利用opencv的SVM进行训练

classifier::classifier(void){
        SVMclf = cv::ml::SVM::create();
    }

classifier::classifier(std::string filename){
        SVMclf = cv::ml::SVM::create();
        SVMclf->load(filename.c_str());
    }

(二)关键点

我们都知道在二维图像上,
Harris、
SIFT、
SURF、
KAZE
常见的三维点云关键点提取算法有一下几种:
ISS3D、
Harris3D、
NARF、
SIFT3D

pcl中的sift等关键点
NARF关键点
  NARF(Normal Aligned Radial Feature)关键点是为了从深度图像中识别物体而提出来的,关键点探测的重要一步是减少特征提取时的搜索空间,把重点放在重要的结构上,对NARF关键点提取过程有以下要求:提取的过程必须将边缘及物体表面变化信息考虑在内;关键点的位置必须稳定,可以被重复探测,即使换了不同的视角;关键点所在的位置必须有稳定的支持区域,可以计算描述子并进行唯一的法向量估计。为了满足以上要求,提出以下探测步骤来进行关键点提取:
  (1)遍历每个深度图像点,通过寻找在近邻区域有深度突变的位置进行边缘检测。
  (2)遍历每个深度图像点,根据近邻区域的表面变化决定一种测度表面变化的系数,以及变化的主方向。
  (3)根据第二步找到的主方向计算兴趣值,表征该方向与其他方向的不同,以及该处表面的变化情况,即该点有多稳定。
  (4)对兴趣值进行平滑过滤。
  (5)进行无最大值压缩找到最终的关键点,即为NARF关键点。

#include <iostream>

#include <pcl/range_image/range_image.h>
#include <pcl/io/pcd_io.h>
#include <pcl/visualization/range_image_visualizer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/features/range_image_border_extractor.h>
#include <pcl/keypoints/narf_keypoint.h>
#include <pcl/console/parse.h>
#include <pcl/common/file_io.h>

typedef pcl::PointXYZ PointType;

/* 定义全局变量 */
float angular_resolution = 0.5f;    // 角坐标分辨率
float support_size = 0.2f;          // 感兴趣点的尺寸(球面的直径)
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;  //坐标框架:相机框架(而不是激光框架)
bool setUnseenToMaxRange = false;   // 是否将所有不可见的点看作最大距离


void printUsage (const char* progName)
{
  std::cout << "\n\nUsage: "<<progName<<" [options] <scene.pcd>\n\n"
            << "Options:\n"
            << "-------------------------------------------\n"
            << "-r <float>   angular resolution in degrees (default "<<angular_resolution<<")\n"
            << "-c <int>     coordinate frame (default "<< (int)coordinate_frame<<")\n"
            << "-m           Treat all unseen points as maximum range readings\n"
            << "-s <float>   support size for the interest points (diameter of the used sphere - "
            <<                                                     "default "<<support_size<<")\n"
            << "-h           this help\n"
            << "\n\n";
}

int main (int argc, char** argv)
{

    /* 解析命令行参数 */
    if (pcl::console::find_argument (argc, argv, "-h") >= 0)
    {
        printUsage (argv[0]);
        return 0;
    }
    if (pcl::console::find_argument (argc, argv, "-m") >= 0)
    {
        setUnseenToMaxRange = true;
        std::cout << "Setting unseen values in range image to maximum range readings.\n";
    }
    int tmp_coordinate_frame;
    if (pcl::console::parse (argc, argv, "-c", tmp_coordinate_frame) >= 0)
    {
        coordinate_frame = pcl::RangeImage::CoordinateFrame (tmp_coordinate_frame);
        std::cout << "Using coordinate frame "<< (int)coordinate_frame<<".\n";
    }
    if (pcl::console::parse (argc, argv, "-s", support_size) >= 0)
        std::cout << "Setting support size to "<<support_size<<".\n";
    if (pcl::console::parse (argc, argv, "-r", angular_resolution) >= 0)
        std::cout << "Setting angular resolution to "<<angular_resolution<<"deg.\n";
    angular_resolution = pcl::deg2rad (angular_resolution);
    
    /* 读取pcd文件;如果没有指定文件,就创建样本点 */
    pcl::PointCloud<PointType>::Ptr point_cloud_ptr (new pcl::PointCloud<PointType>);
    pcl::PointCloud<PointType>& point_cloud = *point_cloud_ptr;
    pcl::PointCloud<pcl::PointWithViewpoint> far_ranges;
    Eigen::Affine3f scene_sensor_pose (Eigen::Affine3f::Identity ());
    std::vector<int> pcd_filename_indices = pcl::console::parse_file_extension_argument (argc, argv, "pcd");
    if (!pcd_filename_indices.empty ())
    {
        std::string filename = argv[pcd_filename_indices[0]];
        if (pcl::io::loadPCDFile (filename, point_cloud) == -1)
        {
            std::cerr << "Was not able to open file \""<<filename<<"\".\n";
            printUsage (argv[0]);
            return 0;
        }
        scene_sensor_pose = Eigen::Affine3f (Eigen::Translation3f (point_cloud.sensor_origin_[0],
                                                                   point_cloud.sensor_origin_[1],
                                                                   point_cloud.sensor_origin_[2])) *
                            Eigen::Affine3f (point_cloud.sensor_orientation_);
        std::string far_ranges_filename = pcl::getFilenameWithoutExtension (filename)+"_far_ranges.pcd";
        if (pcl::io::loadPCDFile (far_ranges_filename.c_str (), far_ranges) == -1)
            std::cout << "Far ranges file \""<<far_ranges_filename<<"\" does not exists.\n";
    }
    else
    {
        setUnseenToMaxRange = true;
        std::cout << "\nNo *.pcd file given => Generating example point cloud.\n\n";
        for (float x=-0.5f; x<=0.5f; x+=0.01f)
        {
            for (float y=-0.5f; y<=0.5f; y+=0.01f)
            {
                PointType point;  point.x = x;  point.y = y;  point.z = 2.0f - y;
                point_cloud.points.push_back (point);
            }
        }
        point_cloud.width = point_cloud.size ();  point_cloud.height = 1;
    }
    
    /* 从点云数据,创建深度图像 */
    float noise_level = 0.0;
    float min_range = 0.0f;
    int border_size = 1;
    pcl::RangeImage::Ptr range_image_ptr (new pcl::RangeImage);
    pcl::RangeImage& range_image = *range_image_ptr;   
    range_image.createFromPointCloud (point_cloud, angular_resolution, pcl::deg2rad (360.0f), pcl::deg2rad (180.0f),
                                    scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size);
    range_image.integrateFarRanges (far_ranges);
    if (setUnseenToMaxRange)
        range_image.setUnseenToMaxRange ();
    
    /* 打开3D可视化窗口,并添加点云 */
    pcl::visualization::PCLVisualizer viewer ("3D Viewer");
    viewer.setBackgroundColor (1, 1, 1);
    pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> range_image_color_handler (range_image_ptr, 0, 0, 0);
    viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image");
    viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "range image");
    //viewer.addCoordinateSystem (1.0f, "global");
    //PointCloudColorHandlerCustom<PointType> point_cloud_color_handler (point_cloud_ptr, 150, 150, 150);
    //viewer.addPointCloud (point_cloud_ptr, point_cloud_color_handler, "original point cloud");
    viewer.initCameraParameters ();
    //setViewerPose (viewer, range_image.getTransformationToWorldSystem ());
    
    /* 显示深度图像 */
    pcl::visualization::RangeImageVisualizer range_image_widget ("Range image");
    range_image_widget.showRangeImage (range_image);
    
    /* 提取NARF关键点 */
    pcl::RangeImageBorderExtractor range_image_border_extractor;    // 创建深度图像的边界提取器,用于提取NARF关键点
    pcl::NarfKeypoint narf_keypoint_detector (&range_image_border_extractor);   // 创建NARF对象
    narf_keypoint_detector.setRangeImage (&range_image);
    narf_keypoint_detector.getParameters ().support_size = support_size;
    //narf_keypoint_detector.getParameters ().add_points_on_straight_edges = true;
    //narf_keypoint_detector.getParameters ().distance_for_additional_points = 0.5;
    
    pcl::PointCloud<int> keypoint_indices;              // 用于存储关键点的索引
    narf_keypoint_detector.compute (keypoint_indices);  // 计算NARF关键点
    std::cout << "Found "<<keypoint_indices.size ()<<" key points.\n";

    /* 在range_image_widget中显示关键点 */
    //for (std::size_t i=0; i<keypoint_indices.size (); ++i)
        //range_image_widget.markPoint (keypoint_indices[i]%range_image.width,
                                    //keypoint_indices[i]/range_image.width);
    
    /* 在3D viwer窗口中显示关键点 */
    pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints_ptr (new pcl::PointCloud<pcl::PointXYZ>);
    pcl::PointCloud<pcl::PointXYZ>& keypoints = *keypoints_ptr;
    keypoints.resize (keypoint_indices.size ());
    for (std::size_t i=0; i<keypoint_indices.size (); ++i)
        keypoints[i].getVector3fMap () = range_image[keypoint_indices[i]].getVector3fMap ();

    pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> keypoints_color_handler (keypoints_ptr, 0, 255, 0);
    viewer.addPointCloud<pcl::PointXYZ> (keypoints_ptr, keypoints_color_handler, "keypoints");
    viewer.setPointCloudRenderingProperties (pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "keypoints");
    
    while (!viewer.wasStopped ())
    {
        range_image_widget.spinOnce ();  // 处理GUI事件
        viewer.spinOnce ();
        pcl_sleep(0.01);
    }
}

NARF 深度图关键点
在这里插入图片描述
Harris算子是常见的特征检测算子,既可以提取角点也可以提取边缘点。与2D Harris角点检测原理不同,3D Harris角点检测利用的是点云法向量的信息。

#include <iostream>
#include <pcl/io/pcd_io.h>
#include <pcl/point_cloud.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/io/io.h>
#include <pcl/keypoints/harris_3d.h>    //harris特征点估计类头文件声明
#include <cstdlib>
#include <vector>
#include <pcl/console/parse.h>

using namespace std;

int main(int argc,char *argv[]) 
{
	pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ>);
	pcl::io::loadPCDFile ("../pcd/room.pcd", *input_cloud);
	pcl::PCDWriter writer;
	float r_normal;
	float r_keypoint;

	r_normal=stof(argv[2]);
	r_keypoint=stof(argv[3]);

	typedef pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZI> ColorHandlerT3;

	pcl::PointCloud<pcl::PointXYZI>::Ptr Harris_keypoints (new pcl::PointCloud<pcl::PointXYZI> ());
	pcl::HarrisKeypoint3D<pcl::PointXYZ,pcl::PointXYZI,pcl::Normal>* harris_detector = new pcl::HarrisKeypoint3D<pcl::PointXYZ,pcl::PointXYZI,pcl::Normal> ;

	//harris_detector->setNonMaxSupression(true);
	harris_detector->setRadius(r_normal);
	harris_detector->setRadiusSearch(r_keypoint);
	harris_detector->setInputCloud (input_cloud);
	//harris_detector->setNormals(normal_source);
	//harris_detector->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::LOWE);
	harris_detector->compute (*Harris_keypoints);
	cout<< "Harris_keypoints的大小是" << Harris_keypoints->size() <<endl;
	writer.write<pcl::PointXYZI> ("Harris_keypoints.pcd", *Harris_keypoints, false);

	pcl::visualization::PCLVisualizer visu3("clouds");
	visu3.setBackgroundColor(255,255,255);
	visu3.addPointCloud (Harris_keypoints, ColorHandlerT3 (Harris_keypoints, 0.0, 0.0, 255.0), "Harris_keypoints");
	visu3.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE,8,"Harris_keypoints");
	visu3.addPointCloud(input_cloud,"input_cloud");
	visu3.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR,0,0,0,"input_cloud");
	visu3.spin ();
}

在这里插入图片描述

自定义特征

例如:

相差较大的物体,利用特征值区别

如果面状性较好的话,可以知道会有两个特征值大小接近,一个特征值很小;
如果点云很分散的话,那么3个特征值的大小应该是比较接近的。
在这里插入图片描述

https://blog.csdn.net/CVSvsvsvsvs/article/details/85784438

例如:
多分类mnist用法

#include <stdio.h>  
#include <time.h>  
#include <opencv2/opencv.hpp>  
#include <opencv/cv.h>  
#include <iostream> 
#include <opencv2/core/core.hpp>  
#include <opencv2/highgui/highgui.hpp>  
#include <opencv2/ml/ml.hpp>  
 
 
 
using namespace std;
using namespace cv;
using namespace ml;
 
Mat dealimage;
Mat src;
Mat yangben_gray;
Mat yangben_thresh;
 
int ReverseInt(int i)
{
	unsigned char ch1, ch2, ch3, ch4;
	ch1 = i & 255;
	ch2 = (i >> 8) & 255;
	ch3 = (i >> 16) & 255;
	ch4 = (i >> 24) & 255;
	return((int)ch1 << 24) + ((int)ch2 << 16) + ((int)ch3 << 8) + ch4;
}
 
void read_Mnist_Label(string filename, Mat* &trainLabel)
{
	ifstream file(filename, ios::binary);
	if (file.is_open())
	{
		int magic_number = 0;
		int number_of_images = 0;
		file.read((char*)&magic_number, sizeof(magic_number));
		file.read((char*)&number_of_images, sizeof(number_of_images));
		magic_number = ReverseInt(magic_number);
		number_of_images = ReverseInt(number_of_images);
		cout << "magic number = " << magic_number << endl;
		cout << "number of images = " << number_of_images << endl;
 
		trainLabel = new Mat(number_of_images, 1, CV_32SC1);
 
		for (int i = 0; i < number_of_images; i++)
		{
			unsigned char label = 0;
			file.read((char*)&label, sizeof(label));
			if (label > 0) label = 255;
			trainLabel->at<float>(i, 0) = label;
			//cout << "Label: " << labels[i] << endl;
		}
 
	}
}
 
void read_Mnist_Images(string filename, Mat* &trainImages)
{
	ifstream file(filename, ios::binary);
	if (file.is_open())
	{
		int magic_number = 0;
		int number_of_images = 0;
		int n_rows = 0;
		int n_cols = 0;
		file.read((char*)&magic_number, sizeof(magic_number));
		file.read((char*)&number_of_images, sizeof(number_of_images));
		file.read((char*)&n_rows, sizeof(n_rows));
		file.read((char*)&n_cols, sizeof(n_cols));
		magic_number = ReverseInt(magic_number);
		number_of_images = ReverseInt(number_of_images);
		n_rows = ReverseInt(n_rows);
		n_cols = ReverseInt(n_cols);
 
		cout << "magic number = " << magic_number << endl;
		cout << "number of images = " << number_of_images << endl;
		cout << "rows = " << n_rows << endl;
		cout << "cols = " << n_cols << endl;
 
		trainImages = new Mat(number_of_images, n_rows * n_cols, CV_32F);
 
		for (int i = 0; i < number_of_images; i++)
		{
			for (int r = 0; r < n_rows; r++)
			{
				for (int c = 0; c < n_cols; c++)
				{
					unsigned char image = 0;
					file.read((char*)&image, sizeof(image));
					if (image > 0) image = 255;
					trainImages->at<float>(i, r * n_cols + c) = image;
					//if (i == 9999) cout << "IMAGE: " << i << " " << r * n_cols + c  << " " << images[i][r * n_cols + c ] << endl;
					//cout << images[i][r * n_cols + c] << endl;
				}
			}
		}
	}
}
 
 
int main()
{
	cout << "训练数据请输入 1, 直接使用训练模型预测输入2" << endl;
	string flag = "";
 
	while (1) {
		cin >> flag;
		if (flag == "1" || flag == "2")
			break;
		else {
			cout << "输入1,2" << endl;
		}
	}
 
	// 创建分类器并设置参数
	Ptr<SVM> SVM_params = SVM::create();
 
	if (flag == "1") {
		// 训练 加载模型
		// 读取训练样本的数据
		Mat* trainingDataMat = nullptr;
		read_Mnist_Images("mnist_dataset/train-images.idx3-ubyte", trainingDataMat);
 
		//训练样本的响应值  
		Mat* responsesMat = nullptr;
		read_Mnist_Label("mnist_dataset/train-labels.idx1-ubyte", responsesMat);
 
		===============================创建SVM模型===============================
		cout << SVM_params->getVarCount() << " " << endl;
		SVM_params->setType(SVM::C_SVC);     //C_SVC用于分类,C_SVR用于回归
		SVM_params->setKernel(SVM::RBF);  //LINEAR线性核函数。SIGMOID为高斯核函数
 
		// 注释掉部分对本项目不影响,影响因子只有两个
		//SVM_params->setDegree(0);            //核函数中的参数degree,针对多项式核函数;
		SVM_params->setGamma(0.50625);       //核函数中的参数gamma,针对多项式/RBF/SIGMOID核函数; 
		//SVM_params->setCoef0(0);             //核函数中的参数,针对多项式/SIGMOID核函数;
		SVM_params->setC(12.5);              //SVM最优问题参数,设置C-SVC,EPS_SVR和NU_SVR的参数;
		//SVM_params->setNu(0);                //SVM最优问题参数,设置NU_SVC, ONE_CLASS 和NU_SVR的参数; 
		//SVM_params->setP(0);                 //SVM最优问题参数,设置EPS_SVR 中损失函数p的值. 
		//结束条件,即训练1000次或者误差小于0.01结束
		SVM_params->setTermCriteria(TermCriteria(TermCriteria::MAX_ITER + TermCriteria::EPS, 1000, 0.01));
		//Mat* responsesTransfer = new Mat(responsesMat->size().height, 1, CV_32FC1);
 
		//responsesMat->convertTo(*responsesMat, CV_32SC1);      类型为CV_32SC1,此处省略是因为读取的时候已指明该格式了。
		//trainingDataMat->convertTo(*trainingDataMat, CV_32F);  此处需要注意训练数据类型为 CV_32F
 
		//训练数据和标签的结合
		cout << "开始训练" << endl;
		cout << "训练数据长度" << trainingDataMat->size().width << " 高度 " << trainingDataMat->size().height << endl;
		cout << "标签数据长度" << responsesMat->size().width << " 高度 " << responsesMat->size().height << endl;
 
		Ptr<TrainData> tData = TrainData::create(*trainingDataMat, ROW_SAMPLE, *responsesMat);
 
		// 训练分类器
		SVM_params->train(tData);//训练
		SVM_params->save("svm.xml");
		cout << SVM_params->getVarCount() << " " << endl;
 
		//保存模型
		SVM_params->save("svm.xml");
		cout << "训练好了!!!" << endl;
		delete trainingDataMat;
		delete responsesMat;
		trainingDataMat = NULL;
		responsesMat = NULL;
	}
	else if (flag == "2") {
		cout << "训练模型参数加载" << endl;
		SVM_params = SVM::load("svm.xml");
		//cout << SVM_params.empty() << endl;
	}
	
 
 
	cout << "-------SVM 开始预测-------------------------------" << endl;
 
	int count = 0;   // 统计正确率
	Mat* testImage = nullptr;
	Mat* testLabel = nullptr;
 
	read_Mnist_Images("mnist_dataSet/t10k-images.idx3-ubyte", testImage);
	read_Mnist_Label("mnist_dataSet/t10k-labels.idx1-ubyte", testLabel);
 
	int height = testImage->size().height;  // 测试图片的数量
	int width = testImage->size().width;    // 图片的维度
 
	for (int i = 0; i < height; i++) { // 遍历所有测试图片
		Mat image(1, width, CV_32F);  // 单张图片
		for (int j = 0; j < width; j++) { //
			image.at<float>(0, j) = testImage->at<float>(i, j);
		}
		//cout << image.size().height << " " << image.size().width << " " << endl;
		//cout << image.cols << " " << image.rows << " " << endl;
		//cout << SVM_params->getVarCount() << " " << endl;
		if (SVM_params->predict(image) == testLabel[i]) {
			count++;
		}
 
	}
	cout << "训练预测的准确率为:" << (double)count / height << endl;
	system("pause");
	//waitKey(0);
	return 0;
}
 

2:深度神经网络

ModelNet40数据集

在这里插入图片描述

在这里插入图片描述
在这里插入图片描述

ScanObjectNN 数据集

在这里插入图片描述
在这里插入图片描述

CNN方法:

PointNet, DGCNN, PPFNet, PointConv

||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||||
其中 PointNet系列方法
常规的 3* N为输入
N即n个点云数据(x,y,z)
在这里插入图片描述

3D CNN系列方法

例如 利用kears进行模型训练


""" 3D-CNN is initailized to have grid size 40x40x40 """
cnn = CNNModel(ip_shape=(1, 40, 40, 40))
cnn.load_model(base_path=os.path.join(PACKAGE_PATH, "bin/3DCNN_model"))


from keras.preprocessing.image import ImageDataGenerator
from keras.models import Sequential
from keras.layers.core import Dense, Dropout, Activation, Flatten
from keras.layers.convolutional import Conv3D,Convolution3D, MaxPooling3D

from keras.optimizers import SGD, RMSprop
from keras.utils import np_utils, generic_utils
from sklearn.preprocessing import LabelBinarizer
from termprinter import *
from keras.models import model_from_json
import numpy as np
import os

class CNNModel:
    def __init__(self,nb_classes=5,ip_shape=(1, 40, 40, 40)):
        self.encoder = LabelBinarizer()
        self.CNN_model(nb_classes=nb_classes,ip_shape=ip_shape)    

    def CNN_model(self,nb_classes = 5,ip_shape=(1, 40, 40, 40)):
        self.model = Sequential()
        self.model.add(
            Conv3D(32, (5,5,5), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",input_shape=ip_shape,
            activation='relu', dilation_rate=(1, 1, 1) ))
        self.model.add(
            Conv3D(32, (5,5,5), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",
            # activation='relu'))
            activation='sigmoid'))
        
        self.model.add(MaxPooling3D(pool_size=(2,2,2)))
        self.model.add(Dropout(0.1))
        
        self.model.add(
            Conv3D(32, (3,3,3), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",
            # activation='relu'))
            activation='sigmoid'))
        self.model.add(
            Conv3D(32, (3,3,3), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",
            activation='relu'))

        self.model.add(MaxPooling3D(pool_size=(2,2,2)))
        self.model.add(Dropout(0.1))
        
        self.model.add(
            Conv3D(32, (3,3,3), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",
            activation='relu'))
        self.model.add(
            Conv3D(32, (3,3,3), 
            strides=(1, 1, 1), padding='valid', data_format="channels_first",
            activation='relu'))

        self.model.add(MaxPooling3D(pool_size=(2,2,2)))
        self.model.add(Dropout(0.1))
        

        self.model.add(Flatten())
        # self.model.add(Dense(128, init='normal', activation='relu'))
        self.model.add(Dense(128, kernel_initializer='normal', activation='relu'))
        # self.model.add(Dropout(0.5))
        # self.model.add(Dense(nb_classes,init='normal'))
        self.model.add(Dense(nb_classes,kernel_initializer='normal'))
        self.model.add(Activation('softmax'))
        # self.model.compile(loss='categorical_crossentropy', optimizer='RMSprop', metrics=['mse', 'accuracy'])
        self.model.compile(loss='categorical_crossentropy', optimizer='adam', metrics=['mse', 'accuracy'])
        # return self.model
    
    def train(self,data,labels):
        labels = self.encoder.fit_transform(labels)
        hist = self.model.fit(data,labels,batch_size=10, epochs = 10,shuffle=True)  
        
    def test(self,data,labels): 
        labels = self.encoder.fit_transform(labels)
        score = self.model.evaluate(data,labels,batch_size=10)
        print('**********************************************')
        print(OKGREEN+"[{d[0]}]{d[3]}   [{d[1]}]{d[4]}  [{d[2]}]{d[5]}".format(d=self.model.metrics_names+score) + ENDC)

    def predict(self,data,labelsSet):
        _idx = np.argmax(self.model.predict(data))
        return labelsSet[_idx],self.model.predict_proba(data)[0][_idx]

    def save_model(self,base_path="."):
        # serialize model to JSON
        json_path = os.path.join(base_path,'model.json')
        print(OKGREEN+json_path+ENDC)
        model_json = self.model.to_json()
        with open(json_path, "w") as json_file:
            json_file.write(model_json)
        # serialize weights to HDF5
        weight_file = os.path.join(base_path,"model.h5")
        print(OKGREEN+weight_file+ENDC)
        self.model.save_weights(weight_file)
        print("Saved model to disk")

    def load_model(self,base_path="."):
        # load json and create model
        json_path = os.path.join(base_path,'model.json')
        print(OKGREEN+json_path+ENDC)
        json_file = open(json_path, 'r')
        loaded_model_json = json_file.read()
        json_file.close()
        
        self.model = model_from_json(loaded_model_json)
        # load weights into new model
        weight_file = os.path.join(base_path,"model.h5")
        print(OKGREEN+weight_file+ENDC)
        self.model.load_weights(weight_file)
        print(OKGREEN+"Loaded model from disk"+ENDC)

Logo

旨在为数千万中国开发者提供一个无缝且高效的云端环境,以支持学习、使用和贡献开源项目。

更多推荐