Go to the documentation of this file.00001 #ifndef FEATURE_ESTIMATION_H
00002 #define FEATURE_ESTIMATION_H
00003
00004 #include "typedefs.h"
00005
00006 #include <pcl/io/io.h>
00007 #include <pcl/features/normal_3d.h>
00008 #include <pcl/keypoints/sift_keypoint.h>
00009 #include <pcl/features/fpfh.h>
00010 #include <pcl/features/vfh.h>
00011 #include <pcl/search/kdtree.h>
00012
00013
00014
00015
00016
00017
00018
00019
00020 SurfaceNormalsPtr
00021 estimateSurfaceNormals (const PointCloudPtr & input, float radius)
00022 {
00023 pcl::NormalEstimation<PointT, NormalT> normal_estimation;
00024 normal_estimation.setSearchMethod (pcl::search::Search<PointT>::Ptr (new pcl::search::KdTree<PointT>));
00025 normal_estimation.setRadiusSearch (radius);
00026 normal_estimation.setInputCloud (input);
00027 SurfaceNormalsPtr normals (new SurfaceNormals);
00028 normal_estimation.compute (*normals);
00029
00030 return (normals);
00031 }
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049 PointCloudPtr
00050 detectKeypoints (const PointCloudPtr & points, const SurfaceNormalsPtr & normals,
00051 float min_scale, int nr_octaves, int nr_scales_per_octave, float min_contrast)
00052 {
00053 pcl::SIFTKeypoint<PointT, pcl::PointWithScale> sift_detect;
00054 sift_detect.setSearchMethod (pcl::search::Search<PointT>::Ptr (new pcl::search::KdTree<PointT>));
00055 sift_detect.setScales (min_scale, nr_octaves, nr_scales_per_octave);
00056 sift_detect.setMinimumContrast (min_contrast);
00057 sift_detect.setInputCloud (points);
00058 pcl::PointCloud<pcl::PointWithScale> keypoints_temp;
00059 sift_detect.compute (keypoints_temp);
00060 PointCloudPtr keypoints (new PointCloud);
00061 pcl::copyPointCloud (keypoints_temp, *keypoints);
00062
00063 return (keypoints);
00064 }
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078 LocalDescriptorsPtr
00079 computeLocalDescriptors (const PointCloudPtr & points, const SurfaceNormalsPtr & normals,
00080 const PointCloudPtr & keypoints, float feature_radius)
00081 {
00082 pcl::FPFHEstimation<PointT, NormalT, LocalDescriptorT> fpfh_estimation;
00083 fpfh_estimation.setSearchMethod (pcl::search::Search<PointT>::Ptr (new pcl::search::KdTree<PointT>));
00084 fpfh_estimation.setRadiusSearch (feature_radius);
00085 fpfh_estimation.setSearchSurface (points);
00086 fpfh_estimation.setInputNormals (normals);
00087 fpfh_estimation.setInputCloud (keypoints);
00088 LocalDescriptorsPtr local_descriptors (new LocalDescriptors);
00089 fpfh_estimation.compute (*local_descriptors);
00090
00091 return (local_descriptors);
00092 }
00093
00094
00095
00096
00097
00098
00099
00100
00101
00102 GlobalDescriptorsPtr
00103 computeGlobalDescriptor (const PointCloudPtr & points, const SurfaceNormalsPtr & normals)
00104 {
00105 pcl::VFHEstimation<PointT, NormalT, GlobalDescriptorT> vfh_estimation;
00106 vfh_estimation.setSearchMethod (pcl::search::Search<PointT>::Ptr (new pcl::search::KdTree<PointT>));
00107 vfh_estimation.setInputCloud (points);
00108 vfh_estimation.setInputNormals (normals);
00109 GlobalDescriptorsPtr global_descriptor (new GlobalDescriptors);
00110 vfh_estimation.compute (*global_descriptor);
00111
00112 return (global_descriptor);
00113 }
00114
00115
00116 struct ObjectFeatures
00117 {
00118 PointCloudPtr points;
00119 SurfaceNormalsPtr normals;
00120 PointCloudPtr keypoints;
00121 LocalDescriptorsPtr local_descriptors;
00122 GlobalDescriptorsPtr global_descriptor;
00123 };
00124
00125
00126
00127
00128 ObjectFeatures
00129 computeFeatures (const PointCloudPtr & input)
00130 {
00131 ObjectFeatures features;
00132 features.points = input;
00133 features.normals = estimateSurfaceNormals (input, 0.05);
00134 features.keypoints = detectKeypoints (input, features.normals, 0.005, 10, 8, 1.5);
00135 features.local_descriptors = computeLocalDescriptors (input, features.normals, features.keypoints, 0.1);
00136 features.global_descriptor = computeGlobalDescriptor (input, features.normals);
00137
00138 return (features);
00139 }
00140
00141 #endif