隐式形状模型
這個算法由兩部分組成,第一部分是訓練,第二部分是物體識別。它有以下6步:
1.先發現特征點。這只是一個訓練點云的簡化。在這個步驟里面所有的點云都將被簡化,通過體元柵格這個途徑。余下來的點就是特征點。
2.對特征點用FPFH進行預測。
3.通過k-means這個算法進行聚類。
4.計算每一個實例里面的對中心的方向。
5.對每一個視覺信息,數學權重將會被計算。
6.每一個特征點的權重將會被計算。
我們在訓練的過程結束以后,接下來就是對象搜索的進程。
1.特征點檢測。
2.每個點云特征點的特征檢測。
3.對于每個特征搜索最近的視覺信息。
4.對于每一個特征:
對于每一個實例:
???? 對相應的方向進行決策。
5.前面的步驟給了我們一個方向集用來預測中心與能量。
上面的步驟很多涉及機器學習之類的,大致明白那個過程即可
代碼部分:
第一步我們需要點云的訓練集。在下面是一些可以用的訓練集.
Cat (train)
Horse (train)
????????? Lioness (train)
??????????Michael (train)
Wolf (train)
用來檢測的點云:
?????????????????????? Cat
?????????????????????? Horse
??????????????????????? Lioness
??????????????????????? Michael
???????????????????????? Wolf
?
下面是代碼
#include <iostream> #include <pcl/io/pcd_io.h> #include <pcl/features/normal_3d.h> #include <pcl/features/feature.h> #include <pcl/visualization/cloud_viewer.h> #include <pcl/features/fpfh.h> #include <pcl/features/impl/fpfh.hpp> #include <pcl/recognition/implicit_shape_model.h> #include <pcl/recognition/impl/implicit_shape_model.hpp>int main (int argc, char** argv) {if (argc == 0 || argc % 2 == 0)return (-1);unsigned int number_of_training_clouds = (argc - 3) / 2;pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normal_estimator;normal_estimator.setRadiusSearch (25.0);std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> training_clouds;std::vector<pcl::PointCloud<pcl::Normal>::Ptr> training_normals;std::vector<unsigned int> training_classes;for (unsigned int i_cloud = 0; i_cloud < number_of_training_clouds - 1; i_cloud++){pcl::PointCloud<pcl::PointXYZ>::Ptr tr_cloud(new pcl::PointCloud<pcl::PointXYZ> ());if ( pcl::io::loadPCDFile <pcl::PointXYZ> (argv[i_cloud * 2 + 1], *tr_cloud) == -1 )return (-1);pcl::PointCloud<pcl::Normal>::Ptr tr_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared ();normal_estimator.setInputCloud (tr_cloud);normal_estimator.compute (*tr_normals);unsigned int tr_class = static_cast<unsigned int> (strtol (argv[i_cloud * 2 + 2], 0, 10));training_clouds.push_back (tr_cloud);training_normals.push_back (tr_normals);training_classes.push_back (tr_class);}pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >::Ptr fpfh(new pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >);fpfh->setRadiusSearch (30.0);pcl::Feature< pcl::PointXYZ, pcl::Histogram<153> >::Ptr feature_estimator(fpfh);pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal> ism;ism.setFeatureEstimator(feature_estimator);ism.setTrainingClouds (training_clouds);ism.setTrainingNormals (training_normals);ism.setTrainingClasses (training_classes);ism.setSamplingSize (2.0f);pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>::ISMModelPtr model = boost::shared_ptr<pcl::features::ISMModel>(new pcl::features::ISMModel);ism.trainISM (model);std::string file ("trained_ism_model.txt");model->saveModelToFile (file);model->loadModelFromfile (file);unsigned int testing_class = static_cast<unsigned int> (strtol (argv[argc - 1], 0, 10));pcl::PointCloud<pcl::PointXYZ>::Ptr testing_cloud (new pcl::PointCloud<pcl::PointXYZ> ());if ( pcl::io::loadPCDFile <pcl::PointXYZ> (argv[argc - 2], *testing_cloud) == -1 )return (-1);pcl::PointCloud<pcl::Normal>::Ptr testing_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared ();normal_estimator.setInputCloud (testing_cloud);normal_estimator.compute (*testing_normals);boost::shared_ptr<pcl::features::ISMVoteList<pcl::PointXYZ> > vote_list = ism.findObjects (model,testing_cloud,testing_normals,testing_class);double radius = model->sigmas_[testing_class] * 10.0;double sigma = model->sigmas_[testing_class];std::vector<pcl::ISMPeak, Eigen::aligned_allocator<pcl::ISMPeak> > strongest_peaks;vote_list->findStrongestPeaks (strongest_peaks, testing_class, radius, sigma);pcl::PointCloud <pcl::PointXYZRGB>::Ptr colored_cloud = (new pcl::PointCloud<pcl::PointXYZRGB>)->makeShared ();colored_cloud->height = 0;colored_cloud->width = 1;pcl::PointXYZRGB point;point.r = 255;point.g = 255;point.b = 255;for (size_t i_point = 0; i_point < testing_cloud->points.size (); i_point++){point.x = testing_cloud->points[i_point].x;point.y = testing_cloud->points[i_point].y;point.z = testing_cloud->points[i_point].z;colored_cloud->points.push_back (point);}colored_cloud->height += testing_cloud->points.size ();point.r = 255;point.g = 0;point.b = 0;for (size_t i_vote = 0; i_vote < strongest_peaks.size (); i_vote++){point.x = strongest_peaks[i_vote].x;point.y = strongest_peaks[i_vote].y;point.z = strongest_peaks[i_vote].z;colored_cloud->points.push_back (point);}colored_cloud->height += strongest_peaks.size ();pcl::visualization::CloudViewer viewer ("Result viewer");viewer.showCloud (colored_cloud);while (!viewer.wasStopped ()){}return (0); }1.首先加載用于訓練的點云
for (unsigned int i_cloud = 0; i_cloud < number_of_training_clouds - 1; i_cloud++){pcl::PointCloud<pcl::PointXYZ>::Ptr tr_cloud(new pcl::PointCloud<pcl::PointXYZ> ());if ( pcl::io::loadPCDFile <pcl::PointXYZ> (argv[i_cloud * 2 + 1], *tr_cloud) == -1 )return (-1);pcl::PointCloud<pcl::Normal>::Ptr tr_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared ();normal_estimator.setInputCloud (tr_cloud);normal_estimator.compute (*tr_normals);unsigned int tr_class = static_cast<unsigned int> (strtol (argv[i_cloud * 2 + 2], 0, 10));training_clouds.push_back (tr_cloud);training_normals.push_back (tr_normals);training_classes.push_back (tr_class);}2.創建特征評估器的實例。
pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >::Ptr fpfh(new pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::Histogram<153> >);fpfh->setRadiusSearch (30.0);pcl::Feature< pcl::PointXYZ, pcl::Histogram<153> >::Ptr feature_estimator(fpfh);3.創建pcl::ism::ImplicitShapeModeEstimation的實例。
ism.setFeatureEstimator(feature_estimator);ism.setTrainingClouds (training_clouds);ism.setTrainingNormals (training_normals);ism.setTrainingClasses (training_classes);ism.setSamplingSize (2.0f);4.這個實例將輸入訓練集和特征預估器
pcl::ism::ImplicitShapeModelEstimation<153, pcl::PointXYZ, pcl::Normal>::ISMModelPtr model = boost::shared_ptr<pcl::features::ISMModel>(new pcl::features::ISMModel);ism.trainISM (model);上面這些將簡化訓練過程的啟動
5.把訓練模型存到文件里面為了使代碼復用
std::string file ("trained_ism_model.txt");model->saveModelToFile (file);6.從文件里面加載模型。
model->loadModelFromfile (file);7.分類操作的點云和法線也需要訓練的過程。
unsigned int testing_class = static_cast<unsigned int> (strtol (argv[argc - 1], 0, 10));pcl::PointCloud<pcl::PointXYZ>::Ptr testing_cloud (new pcl::PointCloud<pcl::PointXYZ> ());if ( pcl::io::loadPCDFile <pcl::PointXYZ> (argv[argc - 2], *testing_cloud) == -1 )return (-1);pcl::PointCloud<pcl::Normal>::Ptr testing_normals = (new pcl::PointCloud<pcl::Normal>)->makeShared ();normal_estimator.setInputCloud (testing_cloud);normal_estimator.compute (*testing_normals);8.啟動分類的進程。代碼將會告訴算法去找testing_class類型的物體,在給定的testing_cloud這個點云里面。注意算法將會使用任何你放進去進行訓練的模型。在分類操作以后,一列的決策將會以pcl::ism::ISMVoteList這個形式返回。
double radius = model->sigmas_[testing_class] * 10.0;double sigma = model->sigmas_[testing_class];std::vector<pcl::ISMPeak, Eigen::aligned_allocator<pcl::ISMPeak> > strongest_peaks;vote_list->findStrongestPeaks (strongest_peaks, testing_class, radius, sigma);上面的代碼將會找到決策里面的最好的峰值。
運行下面的代碼
./implicit_shape_modelism_train_cat.pcd 0ism_train_horse.pcd 1ism_train_lioness.pcd 2ism_train_michael.pcd 3ism_train_wolf.pcd 4ism_test_cat.pcd 0最后的參數是你要檢測的點云和你感興趣的類別。(比如貓)
~接下去你會看到?
紅點表示物體的中心。
如果你想要可視化決策的過程,你就會看到如下的東西。藍色是決策點
?
?
總結
- 上一篇: 阶段项目:学生信息管理系统数据库设计
- 下一篇: 【youcans 的 OpenCV 例程