test_amplitude_filter.cpp
Go to the documentation of this file.
00001 
00059 /*
00060  * amp_conf_filter_test.cpp
00061  *
00062  *  Created on: Apr 18, 2011
00063  *      Author: goa-wq
00064  */
00065 
00066 //AmplitudeFilter
00067 #include <cob_3d_mapping_filters/amplitude_filter.h>
00068 //#include <cob_3d_mapping_filters/impl/amplitude_filter.hpp>
00069 
00070 #include <pcl/point_types.h>
00071 #include <pcl/io/pcd_io.h>
00072 #include <cob_3d_mapping_common/point_types.h>
00073 //#include <sensor_msgs/point_cloud_conversion.h>
00074 
00075 #include <boost/timer.hpp>
00076 #include "cob_3d_mapping_common/stop_watch.h"
00077 #include <iostream>
00078 #include <fstream>
00079 
00080 /* Methods for testing filters */
00081 
00082 double
00083 TestProcessingTimeOnce (unsigned int cloud_size, unsigned int iterations)
00084 {
00085   cob_3d_mapping_filters::AmplitudeFilter<PointXYZA> filter;
00086   pcl::PointCloud<PointXYZA>::Ptr cloud (new pcl::PointCloud<PointXYZA> ());
00087   pcl::PointCloud<PointXYZA>::Ptr cloud_out (new pcl::PointCloud<PointXYZA> ());
00088 
00089   cloud->points.resize (cloud_size);
00090   cloud->width = cloud_size;
00091   cloud->height = 1;
00092   for (unsigned int i = 0; i < cloud_size; i++)
00093   {
00094     PointXYZA pt;
00095     pt.x = pt.y = pt.z = pt.amplitude = 1;
00096     cloud->points[i] = pt;
00097   }
00098   filter.setInputCloud (cloud);
00099   //boost::timer t;
00100   double time = 0;
00101   for (unsigned int i = 0; i < iterations; i++)
00102   {
00103     PrecisionStopWatch sw;
00104     sw.precisionStart ();
00105     filter.filter (*cloud_out);
00106     time += sw.precisionStop ();
00107   }
00108   time /= iterations;
00109   std::cout << "Cloud size " << cloud_size << ": " << time << " s" << std::endl;
00110   return time;
00111 }
00112 
00113 void
00114 TestProcessingTime ()
00115 {
00116   std::ofstream file;
00117   file.open ("/home/goa/tmp/amplitude_filter_timing.dat");
00118   file << "#No. of points\ttime (s)\n";
00119   for (unsigned int cloud_size = 40000; cloud_size <= 400000; cloud_size += 40000)
00120   {
00121     double time = TestProcessingTimeOnce (cloud_size, 1000);
00122     file << cloud_size << "\t" << time << "\n";
00123   }
00124   file.close ();
00125 }
00126 
00127 void
00128 DoSampleRun ()
00129 {
00130   cob_3d_mapping_filters::AmplitudeFilter<PointXYZA> filter;
00131   pcl::PointCloud<PointXYZA>::Ptr cloud (new pcl::PointCloud<PointXYZA> ());
00132   pcl::PointCloud<PointXYZA>::Ptr cloud_out (new pcl::PointCloud<PointXYZA> ());
00133   pcl::io::loadPCDFile ("/home/goa/Ubuntu One/diss/images/raw/filter_sequence_jumpedge2.pcd", *cloud);
00134   filter.setFilterLimits (0.05, 1);
00135   filter.setInputCloud (cloud);
00136   filter.filter (*cloud_out);
00137   pcl::io::savePCDFileASCII ("/home/goa/Ubuntu One/diss/images/raw/filter_sequence_amplitude2.pcd", *cloud_out);
00138 }
00139 
00140 int
00141 main ()
00142 {
00143   DoSampleRun ();
00144   //TestProcessingTimeOnce(10000,1);
00145 }
00146 


cob_3d_mapping_filters
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:54