LAMPCAE/src/WBCLFZSystemModule/PointCloudProcess/PointCloudAlg.h

268 lines
7.5 KiB
C
Raw Normal View History

#pragma once
#include <QAction>
#include <QCloseEvent>
#include <QColor>
#include <QComboBox>
#include <QDateTime>
#include <QDebug>
#include <QDesktopWidget>
#include <QFileDialog>
#include <QFontComboBox>
#include <QImage>
#include <QLabel>
#include <QMainWindow>
#include <QMenu>
#include <QMenuBar>
#include <QMessageBox>
#include <QProgressDialog>
#include <QRect>
#include <QSettings>
#include <QSpinBox>
#include <QString>
#include <QStringList>
#include <QTextCharFormat>
#include <QTime>
#include <QToolBar>
#include <QToolButton>
#include <QListWidgetItem>
#include <QApplication>
#include <QDateTime> //<2F><><EFBFBD><EFBFBD>QDateTimeͷ<65>ļ<EFBFBD>
#include <QMovie>
#include <QPixmap>
#include <QSplashScreen>
#include <QTextCodec>
// Point Cloud Library
#include <QColorDialog>
#include <iostream>
#include <pcl/common/common.h>
#include <pcl/console/time.h> // TicToc
#include <pcl/console/time.h>
#include <pcl/filters/convolution_3d.h>
#include <pcl/filters/filter.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/filters/statistical_outlier_removal.h>
#include <pcl/io/pcd_io.h>
#include <pcl/io/ply_io.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <boost/random.hpp> //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
#include <boost/thread/thread.hpp>
#include <iostream>
#include <pcl/console/time.h> // TicToc
#include <pcl/features/normal_3d.h>
#include <pcl/filters/bilateral.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/fast_bilateral.h>
#include <pcl/filters/fast_bilateral_omp.h>
#include <pcl/filters/passthrough.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/io/pcd_io.h>
#include <pcl/io/ply_io.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/registration/ia_fpcs.h> // 4PCS<43>
#include <pcl/registration/ia_kfpcs.h> //K4PCS<43>㷨ͷ<E3B7A8>ļ<EFBFBD>
#include <pcl/registration/icp.h>
#include <pcl/registration/registration.h>
#include <pcl/search/flann_search.h>
#include <pcl/surface/concave_hull.h>
#include <pcl/surface/gp3.h> //̰<><CCB0>ͶӰ<CDB6><D3B0><EFBFBD>ǻ<EFBFBD><C7BB><EFBFBD><EFBFBD><E0B6A8><EFBFBD><EFBFBD>ͷ<EFBFBD>ļ<EFBFBD>
#include <pcl/surface/marching_cubes_hoppe.h> //<2F>ƶ<EFBFBD><C6B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
#include <pcl/surface/marching_cubes_rbf.h>
#include <pcl/surface/mls.h> //MLS
#include <pcl/surface/poisson.h> //<2F><><EFBFBD><EFBFBD><EFBFBD>ؽ<EFBFBD>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <string>
#include <vector>
#include <vtkOutputWindow.h>
#include <pcl/console/time.h> // TicToc
#include <pcl/filters/approximate_voxel_grid.h> // <20><><EFBFBD><EFBFBD><EFBFBD>˲<EFBFBD>
#include <pcl/filters/voxel_grid.h> // <20><><EFBFBD><EFBFBD><EFBFBD>˲<EFBFBD>
#include <vtkOutputWindow.h>
#include <boost/thread/thread.hpp>
#include <pcl/ModelCoefficients.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/method_types.h> //<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ʒ<EFBFBD><C6B7><EFBFBD>
#include <pcl/sample_consensus/model_types.h> //ģ<>Ͷ<EFBFBD><CDB6><EFBFBD>
#include <pcl/segmentation/sac_segmentation.h> //RANSAC<41>ָ<EFBFBD>
#include <pcl/visualization/pcl_visualizer.h>
#include <sstream>
#include <stdlib.h> //rand()ͷ<>ļ<EFBFBD>
#include <vtkMassProperties.h>
#include <vtkPLYReader.h>
#include <vtkSmartPointer.h>
#include <vtkTriangleFilter.h>
#include <Eigen/Core>
#include <iostream>
#include <pcl/common/common.h>
#include <pcl/common/transforms.h>
#include <pcl/features/moment_of_inertia_estimation.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <string>
#include <string>
#include <vector>
#include <vtkAutoInit.h>
//<2F><><EFBFBD>ӻ<EFBFBD><D3BB><EFBFBD><EFBFBD><EFBFBD>ͷ<EFBFBD>ļ<EFBFBD>
#include <vtkActor.h>
#include <vtkAutoInit.h>
#include <vtkInteractorStyleTrackballCamera.h>
#include <vtkPolyDataMapper.h>
#include <vtkProperty.h>
#include <vtkRenderWindow.h>
#include <vtkRenderWindowInteractor.h>
#include <vtkRenderer.h>
// Boost
#include <boost/math/special_functions/round.hpp>
// Visualization Toolkit (VTK)
#include <vtkRenderWindow.h>
#include "BasePCL.h"
///////////////////////////////////////////////////////////
//// <20><><EFBFBD><EFBFBD> <20><EFBFBD><E3B7A8><EFBFBD><EFBFBD>
//////////////////////////////////////////////////////////
// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>Ʒ<EFBFBD><C6B7><EFBFBD><EFBFBD><EFBFBD>
void NormalEstimation(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr cloud, pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals);
////////////////////////////////////////////////////////////////////
// <20><>Ⱥ<EFBFBD><C8BA> + <20>˲<EFBFBD>
//////////////////////////////////////////////////////////////////
/*
<EFBFBD>²<EFBFBD><EFBFBD><EFBFBD>
*/
void downSampling(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered,
double leafSize = 0.01f);
/*
<EFBFBD><EFBFBD>˹<EFBFBD>˲<EFBFBD>
*/
void gaussian_filter(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered,
double radius);
/*
˫<EFBFBD><EFBFBD><EFBFBD>˲<EFBFBD>1
*/
void bilateralFilter(pcl::PointCloud<pcl::PointXYZRGBA>::Ptr input,
pcl::PointCloud<pcl::PointXYZRGBA>::Ptr output,
float sigma_s,
float sigma_r);
/*
<EFBFBD><EFBFBD>˲<EFBFBD><EFBFBD><EFBFBD>:
<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ܶȵ<EFBFBD><EFBFBD><EFBFBD>ɢ<EFBFBD><EFBFBD><EFBFBD>Ƴ<EFBFBD>
*/
void radius_filter(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered_out,
double RadiusSearch=0.015,
int minNearSearch=35);
/*
ͳ<EFBFBD><EFBFBD><EFBFBD>˲<EFBFBD><EFBFBD><EFBFBD>:
<EFBFBD><EFBFBD><EFBFBD><EFBFBD>ͳ<EFBFBD>Ƶ<EFBFBD><EFBFBD><EFBFBD>ɢ<EFBFBD><EFBFBD><EFBFBD>Ƴ<EFBFBD>
*/
void statistical_filter(
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered,
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered_out,
int meanK= 50,
double StddevThresh=1.0);
/************************************************************************/
/* <20><><EFBFBD><EFBFBD><EFBFBD>ؽ<EFBFBD> */
/************************************************************************/
/*
<EFBFBD>²<EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ƾ<EFBFBD><EFBFBD><EFBFBD>
*/
void MLS(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals);
void Pos(pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals,
pcl::PolygonMesh& mesh,
int Degree = 2,
int Depth = 8,
int IsoDivide = 8,
float SamplesPerNode=3.0,
int SolverDivide=8
);
// ̰<><CCB0><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
void GP(pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals,
pcl::PolygonMesh& mesh,
double SearchRadius=1,
double Mu=2.5,
int MaximumNearestNeighbors=100,
double MaximumSurfaceAngle=M_PI/4.0,
double MinimumAngle=M_PI/18,
double MaximumAngle=M_PI/3
);
//<2F>ƶ<EFBFBD><C6B6><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
void MC(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PolygonMesh& mesh);
/************************************************************************/
/* <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>׼<EFBFBD>㷨 */
/************************************************************************/
//// <20><><EFBFBD><EFBFBD><EFBFBD><EFBFBD>ʹ<EFBFBD>õĵ<C3B5><C4B5><EFBFBD>ָ<EFBFBD><D6B8>
//PointCloudT::Ptr cloud_in; // Original point cloud
//PointCloudT::Ptr cloud_tr; // Transformed point cloud
//PointCloudT::Ptr cloud_RE; // ICP output point cloud
//
////ʹ<><CAB9><EFBFBD><EFBFBD>׼<EFBFBD><D7BC><EFBFBD><EFBFBD>Registration<6F><6E>ʵ<EFBFBD>ֶ<EFBFBD>̬
//pcl::Registration<PointT, PointT>::Ptr ALIGN;
//pcl::IterativeClosestPoint<PointT, PointT>::Ptr icp;
//
////<2F><><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD><EFBFBD>
//int iterations = 1; // Default number of ICP iterations
//// bool next_iteration = false;
/*
<EFBFBD><EFBFBD>ӡ4*4<EFBFBD>ľ<EFBFBD><EFBFBD><EFBFBD>
*/
void print4x4Matrix(const Eigen::Matrix4d& matrix);
// TODO
/*
4*4<EFBFBD>ľ<EFBFBD><EFBFBD><EFBFBD>
*/
QString get4x4MatrixStr(const Eigen::Matrix4d& matrix);