37 #include <pcl/point_cloud.h> 
   38 #include <pcl/point_types.h> 
   39 #include <pcl/sample_consensus/method_types.h> 
   40 #include <pcl/sample_consensus/model_types.h> 
   41 #include <pcl/segmentation/sac_segmentation.h> 
   43 #include <boost/random.hpp> 
   52   std::cerr << 
"Usage: " << 
argv[0] << 
" Iteration Number-of-points Max-iterations Gaussian-noise-variance Outlier-threshold" << std::endl;
 
   57   pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZ>);
 
   58   boost::mt19937 gen = boost::mt19937(
static_cast<unsigned long>(time(0)));
 
   60   boost::variate_generator<
 
   62     boost::normal_distribution<> > rand(gen, dst);
 
   64   const double dx = 0.01;
 
   65   cloud->points.resize(num_points * num_points);
 
   66   for (
size_t i = 0; 
i < num_points; 
i++) {
 
   67     for (
size_t j = 0; j < num_points; j++) {
 
   72       cloud->points[
i * num_points + j] = 
p;
 
   80   std::stringstream ss(
argv);
 
   88   std::stringstream ss(
argv);
 
   94 int main(
int argc, 
char** argv)
 
  106   pcl::SACSegmentation<pcl::PointXYZ> seg;
 
  107   seg.setOptimizeCoefficients (
true);
 
  108   seg.setRadiusLimits(0.0, std::numeric_limits<double>::max ()); 
 
  109   seg.setMethodType (pcl::SAC_RANSAC);
 
  110   seg.setDistanceThreshold (outlier_threshold);
 
  111   seg.setInputCloud(
cloud);
 
  112   seg.setMaxIterations (max_iterations);
 
  113   seg.setModelType (pcl::SACMODEL_PLANE);
 
  114   pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
 
  115   pcl::ModelCoefficients::Ptr 
coefficients (
new pcl::ModelCoefficients);
 
  117   gettimeofday(&
s, 
NULL);
 
  118   for (
size_t i = 0; 
i < iteration; 
i++) {
 
  121   gettimeofday(&e, 
NULL);
 
  123   double time = (e.tv_sec - 
s.tv_sec) + (e.tv_usec - 
s.tv_usec)*1.0E-6;
 
  124   printf(
"%lf,%lf,%d,%d,%d,%f,%f\n", time, time / iteration,
 
  125          iteration, number_of_points * number_of_points, max_iterations, 
variance, outlier_threshold);
 
  126   std::cerr << 
"Took " << time << 
" sec (" << time / iteration << 
" sec for each)" << std::endl;