profile_depth_seg.cpp
Go to the documentation of this file.
00001 
00063 // PCL:
00064 #include <pcl/point_types.h>
00065 #include <pcl/io/pcd_io.h>
00066 #include <pcl/common/file_io.h>
00067 
00068 // stack includes:
00069 #include "cob_3d_mapping_common/stop_watch.h"
00070 #include "cob_3d_mapping_common/point_types.h"
00071 #include "cob_3d_features/organized_normal_estimation_omp.h"
00072 #include "cob_3d_segmentation/depth_segmentation.h"
00073 #include "cob_3d_segmentation/cluster_classifier.h"
00074 
00075 using namespace pcl;
00076 
00077 typedef cob_3d_segmentation::PredefinedSegmentationTypes ST;
00078 
00079 class PerformanceTester
00080 {
00081 public:
00082   PerformanceTester()
00083     : l(new PointCloud<PointLabel>)
00084     , n(new PointCloud<Normal>)
00085     , g(new ST::Graph)
00086   {
00087     one.setOutputLabels(l);
00088     one.setPixelSearchRadius(8,2,2); //radius,pixel,circle
00089     one.setSkipDistantPointThreshold(6.0);
00090     seg.setNormalCloudIn(n);
00091     seg.setLabelCloudInOut(l);
00092     seg.setClusterGraphOut(g);
00093   }
00094 
00095   void
00096   computeForOneCloud(PointCloud<PointXYZRGB>::ConstPtr cloud)
00097   {
00098     PrecisionStopWatch t;
00099     t.precisionStart();
00100     one.setInputCloud(cloud);
00101     one.compute(*n);
00102     std::cout << t.precisionStop() << " | ";
00103     t.precisionStart();
00104     seg.setInputCloud(cloud);
00105     seg.performInitialSegmentation();
00106     seg.refineSegmentation();
00107     std::cout << t.precisionStop() << std::endl;
00108   }
00109 
00110 private:
00111   PointCloud<PointLabel>::Ptr l;
00112   PointCloud<Normal>::Ptr n;
00113   ST::Graph::Ptr g;
00114   cob_3d_segmentation::DepthSegmentation<ST::Graph, ST::Point, ST::Normal, ST::Label> seg;
00115   cob_3d_features::OrganizedNormalEstimationOMP<PointXYZRGB, Normal, PointLabel> one;
00116 
00117 };
00118 
00119 int main (int argc, char** argv)
00120 {
00121   if (argc != 2)
00122   {
00123     std::cout << "Please provide a folder containing multiple pcd files" << std::endl;
00124     return 0;
00125   }
00126 
00127   PerformanceTester pt;
00128   PCDReader r;
00129   std::vector<std::string> files;
00130   getAllPcdFilesInDirectory(argv[1], files);
00131   std::vector<PointCloud<PointXYZRGB>::Ptr> clouds;
00132   for (std::vector<std::string>::iterator it = files.begin(); it != files.end(); ++it)
00133   {
00134     clouds.push_back(PointCloud<PointXYZRGB>::Ptr(new PointCloud<PointXYZRGB>));
00135     r.read( argv[1] + *it, *(clouds.back()) );
00136   }
00137 
00138   int i = 0;
00139   while (i < 20)
00140   {
00141     std::vector<PointCloud<PointXYZRGB>::Ptr>::iterator p = clouds.begin();
00142     std::cout << "Run #"<< i << std::endl;
00143     while(p != clouds.end())
00144     {
00145       pt.computeForOneCloud(*p);
00146       ++p;
00147     }
00148     ++i;
00149   }
00150 
00151   return 0;
00152 }


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03