Go to the documentation of this file.00001
00059 #include <pcl/point_types.h>
00060 #include <pcl/io/pcd_io.h>
00061 #include <pcl/features/integral_image_normal.h>
00062 #include <pcl/visualization/pcl_visualizer.h>
00063 #include <pcl/visualization/point_cloud_handlers.h>
00064
00065 #include "cob_3d_mapping_common/stop_watch.h"
00066 #include "cob_3d_mapping_common/point_types.h"
00067 #include "cob_3d_features/fast_edge_estimation_3d_omp.h"
00068 #include "cob_3d_features/organized_normal_estimation_omp.h"
00069
00070 using namespace pcl;
00071 typedef visualization::PointCloudColorHandlerRGBField<PointXYZRGB> ColorHdlRGB;
00072
00073 int main(int argc, char** argv)
00074 {
00075 PointCloud<PointXYZRGB>::Ptr p(new PointCloud<PointXYZRGB>);
00076 PointCloud<Normal>::Ptr n(new PointCloud<Normal>);
00077 PointCloud<InterestPoint>::Ptr ip(new PointCloud<InterestPoint>);
00078 PrecisionStopWatch t;
00079 std::string file_ = argv[1];
00080 PCDReader r;
00081 if (r.read(file_, *p) == -1) return(0);
00082
00083
00084
00085
00086
00087
00088
00089
00090 t.precisionStart();
00091 cob_3d_features::OrganizedNormalEstimationOMP<PointXYZRGB,Normal,PointLabel> ne;
00092 ne.setPixelSearchRadius(8,2,2);
00093 ne.setInputCloud(p);
00094 PointCloud<PointLabel>::Ptr labels(new PointCloud<PointLabel>);
00095 ne.setOutputLabels(labels);
00096 ne.compute(*n);
00097 std::cout << t.precisionStop() << "s\t for normal estimation" << std::endl;
00098
00099 t.precisionStart();
00100 cob_3d_features::FastEdgeEstimation3DOMP<PointXYZRGB, Normal, InterestPoint> ee3d;
00101 ee3d.setPixelSearchRadius(16,2,4);
00102 ee3d.setInputCloud(p);
00103 ee3d.setInputNormals(n);
00104 ee3d.compute(*ip);
00105 std::cout << t.precisionStop() << "s\t for 3D edge estimation" << std::endl;
00106
00107 for (size_t i = 0; i < ip->points.size(); i++)
00108 {
00109 int col = (ip->points[i].strength) * 255;
00110 if (col > 255)
00111 {
00112 p->points[i].r = 0;
00113 p->points[i].g = 255;
00114 p->points[i].b = 0;
00115 }
00116 else if (col < 0)
00117 {
00118 p->points[i].r = 255;
00119 p->points[i].g = 0;
00120 p->points[i].b = 0;
00121 }
00122 else if (col > 100)
00123 {
00124 p->points[i].r = 0;
00125 p->points[i].g = 0;
00126 p->points[i].b = 255;
00127 }
00128 else
00129 {
00130 p->points[i].r = col;
00131 p->points[i].g = col;
00132 p->points[i].b = col;
00133 }
00134 }
00135
00136 visualization::PCLVisualizer v;
00137 ColorHdlRGB col_hdl(p);
00138 v.setBackgroundColor(0,127,127);
00139 v.addPointCloud<PointXYZRGB>(p,col_hdl, "segmented1");
00140
00141 while(!v.wasStopped())
00142 {
00143 v.spinOnce(100);
00144 usleep(100000);
00145 }
00146
00147 return 0;
00148 }