convolve.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * $Id: convolve.cpp 5358 2012-03-28 00:16:25Z nizar $
00036  */
00037 
00038 #include <pcl/point_types.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/console/parse.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/filters/convolution.h>
00043 #include <pcl/visualization/pcl_visualizer.h>
00044 
00045 void
00046 usage (char ** argv)
00047 {
00048   pcl::console::print_info ("usage: %s <filename> <-r|-c|-s> [-p <borders policy>] [-t <number of threads>] [-d <distance>]\n\n", argv[0]);
00049   pcl::console::print_info ("Where options are:\n");
00050   pcl::console::print_info ("\t\t\t-r convolve rows\n");
00051   pcl::console::print_info ("\t\t\t-c convolve columns\n");
00052   pcl::console::print_info ("\t\t\t-s convolve separate\n");
00053   pcl::console::print_info ("\t\t\t-p borders policy\n");
00054   pcl::console::print_info ("\t\t\t\t Z zero padding, default\n");
00055   pcl::console::print_info ("\t\t\t\t D duplicate borders\n");
00056   pcl::console::print_info ("\t\t\t\t M mirror borders\n");
00057   pcl::console::print_info ("\t\t\t-t optional, number of threads, default 1\n");
00058   pcl::console::print_info ("\t\t\t-d optional, distance threshold, default 0.001\n");
00059 }
00060 
00061 int
00062 main (int argc, char ** argv)
00063 {
00064   int viewport_source, viewport_convolved = 0;
00065   int direction = -1;
00066   int nb_threads = 0;
00067   char border_policy = 'Z';
00068   double threshold = 0.001;
00069   pcl::filters::Convolution<pcl::PointXYZRGB, pcl::PointXYZRGB> convolution;
00070   Eigen::ArrayXf gaussian_kernel(5);
00071   gaussian_kernel << 1.f/16, 1.f/4, 3.f/8, 1.f/4, 1.f/16;
00072   pcl::console::print_info ("convolution kernel:");
00073   for (int i = 0; i < gaussian_kernel.size (); ++i)
00074     pcl::console::print_info (" %f", gaussian_kernel[i]);
00075   pcl::console::print_info ("\n");
00076 
00077   if (argc < 3)
00078   {
00079     usage (argv);
00080     return 1;
00081   }
00082 
00083   // check if user is requesting help
00084   std::string arg (argv[1]);
00085 
00086   if (arg == "--help" || arg == "-h")
00087   {
00088     usage (argv);
00089     return 1;
00090   }
00091 
00092   // user don't need help find convolving direction
00093   // convolve row
00094   if (pcl::console::find_switch (argc, argv, "-r"))
00095     direction = 0;
00096   else
00097   {
00098     // convolve column
00099     if (pcl::console::find_switch (argc, argv, "-c"))
00100       direction = 1;
00101     else
00102       // convolve both
00103       if (pcl::console::find_switch (argc, argv, "-s"))
00104         direction = 2;
00105       else
00106       {
00107         // wrong direction given print usage
00108         usage (argv);
00109         return 1;
00110       }
00111   }
00112 
00113   // number of threads if any
00114   if (pcl::console::parse_argument (argc, argv, "-t", nb_threads) != -1 )
00115   {
00116     if (nb_threads <= 0)
00117       nb_threads = 1;
00118   }
00119   convolution.setNumberOfThreads (nb_threads);
00120 
00121   // borders policy if any
00122   if (pcl::console::parse_argument (argc, argv, "-p", border_policy) != -1 )
00123   {
00124     switch (border_policy)
00125     {
00126       case 'Z' : convolution.setBordersPolicy (pcl::filters::Convolution<pcl::PointXYZRGB, pcl::PointXYZRGB>::BORDERS_POLICY_IGNORE);
00127         break;
00128       case 'M' : convolution.setBordersPolicy (pcl::filters::Convolution<pcl::PointXYZRGB, pcl::PointXYZRGB>::BORDERS_POLICY_MIRROR);
00129         break;
00130       case 'D' : convolution.setBordersPolicy (pcl::filters::Convolution<pcl::PointXYZRGB, pcl::PointXYZRGB>::BORDERS_POLICY_DUPLICATE);
00131         break;
00132       default :
00133       {
00134         usage (argv);
00135         return (1);
00136       }
00137     }
00138   }
00139   else
00140     convolution.setBordersPolicy (pcl::filters::Convolution<pcl::PointXYZRGB, pcl::PointXYZRGB>::BORDERS_POLICY_IGNORE);
00141 
00142   // distance threshold if any
00143   if (pcl::console::parse_argument (argc, argv, "-d", threshold) == -1 )
00144   {
00145     threshold = 0.01;
00146   }
00147   convolution.setDistanceThreshold (static_cast<float> (threshold));
00148 
00149   // all set
00150   // we have file name and convolving direction
00151   pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB> ());
00152   if (pcl::io::loadPCDFile (argv[1], *cloud) == -1)
00153   {
00154     pcl::console::print_error ("Couldn't read file %s \n", argv[1]);
00155     return (-1);
00156   }
00157   cloud->is_dense = false;
00158   convolution.setInputCloud (cloud);
00159   convolution.setKernel (gaussian_kernel);
00160   pcl::PointCloud<pcl::PointXYZRGB>::Ptr convolved (new pcl::PointCloud<pcl::PointXYZRGB> ());
00161   double t0;
00162   pcl::console::print_info ("convolving %s along \n", argv[1]);
00163   std::ostringstream convolved_label;
00164   convolved_label << "convolved along ";
00165   switch (direction)
00166   {
00167     case 0:
00168     {
00169       convolved_label << "rows... ";
00170       t0 = pcl::getTime ();
00171       convolution.convolveRows (*convolved);
00172       break;
00173     }
00174     case 1:
00175     {
00176       convolved_label << "columns... ";
00177       t0 = pcl::getTime ();
00178       convolution.convolveCols (*convolved);
00179       break;
00180     }
00181     case 2:
00182     {
00183       convolved_label << "rows and columns... ";
00184       t0 = pcl::getTime ();
00185       convolution.convolve (*convolved);
00186       break;
00187     }
00188   }
00189   convolved_label << pcl::getTime () - t0 << "s";
00190   // Display
00191   boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("Convolution"));
00192   // viewport stuff
00193   viewer->createViewPort (0, 0, 0.5, 1, viewport_source);
00194   viewer->createViewPort (0.5, 0, 1, 1, viewport_convolved);
00195   viewer->setBackgroundColor (0, 0, 0);
00196 
00197   // Source
00198   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler_source (cloud);
00199   viewer->addPointCloud<pcl::PointXYZRGB> (cloud, color_handler_source, "source", viewport_source);
00200   viewer->addText ("source", 10, 10, "source_label", viewport_source);
00201 
00202   // Convolved
00203   pcl::visualization::PointCloudColorHandlerRGBField<pcl::PointXYZRGB> color_handler_convolved (convolved);
00204   viewer->addPointCloud<pcl::PointXYZRGB> (convolved, color_handler_convolved, "convolved", viewport_convolved);
00205   viewer->addText (convolved_label.str (), 10, 10, "convolved_label", viewport_convolved);
00206   viewer->spin ();
00207   pcl::PCDWriter writer;
00208   writer.write<pcl::PointXYZRGB> ("convolved.pcd", *convolved, false);
00209 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:43