openni_mls_smoothing.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  */
00035 
00036 #include <boost/thread/thread.hpp>
00037 #include <boost/date_time/posix_time/posix_time.hpp>
00038 #include <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/visualization/cloud_viewer.h>
00042 #include <pcl/io/openni_camera/openni_driver.h>
00043 #include <pcl/console/parse.h>
00044 #include <pcl/common/time.h>
00045 #include <pcl/surface/mls_omp.h>
00046 #include <pcl/kdtree/kdtree_flann.h>
00047 
00048 #define FPS_CALC(_WHAT_) \
00049 do \
00050 { \
00051     static unsigned count = 0;\
00052     static double last = pcl::getTime ();\
00053     double now = pcl::getTime (); \
00054     ++count; \
00055     if (now - last >= 1.0) \
00056     { \
00057       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00058       count = 0; \
00059       last = now; \
00060       if (*stop_computing_) std::cout << "Press 's' to start computing!\n"; \
00061     } \
00062 }while(false)
00063 
00064 
00065 int default_polynomial_order = 2;
00066 bool default_use_polynomial_fit = false;
00067 double default_search_radius = 0.0,
00068     default_sqr_gauss_param = 0.0;
00069 
00070 template <typename PointType>
00071 class OpenNISmoothing;
00072 
00073 
00074 void keyboardEventOccurred (const pcl::visualization::KeyboardEvent &event,
00075                             void *stop_void)
00076 {
00077   boost::shared_ptr<bool> stop = *static_cast<boost::shared_ptr<bool>*> (stop_void);
00078   if (event.getKeySym () == "s" && event.keyDown ())
00079   {
00080     *stop = ! *stop;
00081     if (*stop) std::cout << "Computing is now stopped!\n";
00082     else std::cout << "Computing commencing!\n";
00083   }
00084 }
00085 
00086 template <typename PointType>
00087 class OpenNISmoothing
00088 {
00089   public:
00090     typedef pcl::PointCloud<PointType> Cloud;
00091     typedef typename Cloud::Ptr CloudPtr;
00092     typedef typename Cloud::ConstPtr CloudConstPtr;
00093 
00094     OpenNISmoothing (double search_radius, bool sqr_gauss_param_set, double sqr_gauss_param,
00095                      bool use_polynomial_fit, int polynomial_order,
00096                      const std::string& device_id = "")
00097     : viewer ("PCL OpenNI MLS Smoothing")
00098     , device_id_(device_id)
00099     {
00100       // Start 4 threads
00101       smoother_.setNumberOfThreads (4);
00102       smoother_.setSearchRadius (search_radius);
00103       if (sqr_gauss_param_set) smoother_.setSqrGaussParam (sqr_gauss_param);
00104       smoother_.setPolynomialFit (use_polynomial_fit);
00105       smoother_.setPolynomialOrder (polynomial_order);
00106 
00107       typename pcl::search::KdTree<PointType>::Ptr tree (new typename pcl::search::KdTree<PointType> ());
00108       smoother_.setSearchMethod (tree);
00109 
00110       viewer.createViewPort (0.0, 0.0, 0.5, 1.0, viewport_input_);
00111       viewer.setBackgroundColor (0, 0, 0, viewport_input_);
00112       viewer.createViewPort (0.5, 0.0, 1.0, 1.0, viewport_smoothed_);
00113       viewer.setBackgroundColor (0, 0, 0, viewport_smoothed_);
00114 
00115       stop_computing_.reset (new bool(true));
00116       cloud_.reset ();
00117       cloud_smoothed_.reset (new Cloud);
00118     }
00119 
00120     void
00121     cloud_cb_ (const CloudConstPtr& cloud)
00122     {
00123       FPS_CALC ("computation");
00124 
00125       mtx_.lock ();
00126       if (! *stop_computing_)
00127       {
00128         smoother_.setInputCloud (cloud);
00129         smoother_.process (*cloud_smoothed_);
00130       }
00131       cloud_ = cloud;
00132       mtx_.unlock ();
00133     }
00134 
00135 
00136 
00137     void
00138     run ()
00139     {
00140       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00141 
00142       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNISmoothing::cloud_cb_, this, _1);
00143       boost::signals2::connection c = interface->registerCallback (f);
00144 
00145       viewer.registerKeyboardCallback (keyboardEventOccurred, reinterpret_cast<void*> (&stop_computing_));
00146 
00147 
00148       interface->start ();
00149 
00150       while (!viewer.wasStopped ())
00151       {
00152         FPS_CALC ("visualization");
00153         viewer.spinOnce ();
00154 
00155         if (cloud_ && mtx_.try_lock ())
00156         {
00157           if (!viewer.updatePointCloud (cloud_, "input_cloud"))
00158             viewer.addPointCloud (cloud_, "input_cloud", viewport_input_);
00159           if (! *stop_computing_ && !viewer.updatePointCloud (cloud_smoothed_, "smoothed_cloud"))
00160             viewer.addPointCloud (cloud_smoothed_, "smoothed_cloud", viewport_smoothed_);
00161           mtx_.unlock ();
00162         }
00163       }
00164 
00165       interface->stop ();
00166     }
00167 
00168     pcl::MovingLeastSquaresOMP<PointType, PointType> smoother_;
00169     pcl::visualization::PCLVisualizer viewer;
00170     std::string device_id_;
00171     boost::mutex mtx_;
00172     CloudConstPtr cloud_;
00173     CloudPtr cloud_smoothed_;
00174     int viewport_input_, viewport_smoothed_;
00175     boost::shared_ptr<bool> stop_computing_;
00176 };
00177 
00178 void
00179 usage (char ** argv)
00180 {
00181   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00182             << "where options are:\n"
00183             << "                     -search_radius X = sphere radius to be used for finding the k-nearest neighbors used for fitting (default: " << default_search_radius << ")\n"
00184             << "                     -sqr_gauss_param X = parameter used for the distance based weighting of neighbors (recommended = search_radius^2) (default: " << default_sqr_gauss_param << ")\n"
00185             << "                     -use_polynomial_fit X = decides whether the surface and normal are approximated using a polynomial or only via tangent estimation (default: " << default_use_polynomial_fit << ")\n"
00186             << "                     -polynomial_order X = order of the polynomial to be fit (implicitly, use_polynomial_fit = 1) (default: " << default_polynomial_order << ")\n";
00187 
00188   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00189   if (driver.getNumberDevices () > 0)
00190   {
00191     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00192     {
00193       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00194               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00195       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00196            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00197            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00198     }
00199   }
00200   else
00201     cout << "No devices connected." << endl;
00202 }
00203 
00204 int
00205 main (int argc, char ** argv)
00206 {
00207   if (argc < 2)
00208   {
00209     usage (argv);
00210     return 1;
00211   }
00212 
00213   std::string arg (argv[1]);
00214 
00215   if (arg == "--help" || arg == "-h")
00216   {
00217     usage (argv);
00218     return 1;
00219   }
00220 
00221   // Command line parsing
00222   double search_radius = default_search_radius;
00223   double sqr_gauss_param = default_sqr_gauss_param;
00224   bool sqr_gauss_param_set = true;
00225   int polynomial_order = default_polynomial_order;
00226   bool use_polynomial_fit = default_use_polynomial_fit;
00227 
00228   pcl::console::parse_argument (argc, argv, "-search_radius", search_radius);
00229   if (pcl::console::parse_argument (argc, argv, "-sqr_gauss_param", sqr_gauss_param) == -1)
00230     sqr_gauss_param_set = false;
00231   if (pcl::console::parse_argument (argc, argv, "-polynomial_order", polynomial_order) == -1 )
00232     use_polynomial_fit = true;
00233   pcl::console::parse_argument (argc, argv, "-use_polynomial_fit", use_polynomial_fit);
00234 
00235   pcl::OpenNIGrabber grabber (arg);
00236   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00237   {
00238     OpenNISmoothing<pcl::PointXYZRGBA> v (search_radius, sqr_gauss_param_set, sqr_gauss_param, 
00239                                           use_polynomial_fit, polynomial_order, arg);
00240     v.run ();
00241   }
00242   else
00243   {
00244     OpenNISmoothing<pcl::PointXYZ> v (search_radius, sqr_gauss_param_set, sqr_gauss_param,
00245                                       use_polynomial_fit, polynomial_order, arg);
00246     v.run ();
00247   }
00248 
00249   return (0);
00250 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:02