openni_feature_persistence.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) 2009-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #include <boost/thread/thread.hpp>
00039 #include <boost/date_time/posix_time/posix_time.hpp>
00040 #include <pcl/point_cloud.h>
00041 #include <pcl/point_types.h>
00042 #include <pcl/io/openni_grabber.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/io/openni_camera/openni_driver.h>
00045 #include <pcl/console/parse.h>
00046 #include <pcl/common/time.h>
00047 #include <pcl/visualization/cloud_viewer.h>
00048 
00049 #include <pcl/features/multiscale_feature_persistence.h>
00050 #include <pcl/features/fpfh_omp.h>
00051 #include <pcl/filters/voxel_grid.h>
00052 #include <pcl/filters/extract_indices.h>
00053 #include <pcl/features/normal_3d_omp.h>
00054 
00055 
00056 #define FPS_CALC(_WHAT_) \
00057 do \
00058 { \
00059     static unsigned count = 0;\
00060     static double last = pcl::getTime ();\
00061     double now = pcl::getTime (); \
00062     ++count; \
00063     if (now - last >= 1.0) \
00064     { \
00065       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00066       count = 0; \
00067       last = now; \
00068     } \
00069 }while(false)
00070 
00071 const float default_subsampling_leaf_size = 0.02f;
00072 const float default_normal_search_radius = 0.041f;
00073 const double aux [] = {0.21, 0.32};
00074 const std::vector<double> default_scales_vector (aux, aux + 2);
00075 const float default_alpha = 1.2f;
00076 
00077 template <typename PointType>
00078 class OpenNIFeaturePersistence
00079 {
00080   public:
00081     typedef pcl::PointCloud<PointType> Cloud;
00082     typedef typename Cloud::Ptr CloudPtr;
00083     typedef typename Cloud::ConstPtr CloudConstPtr;
00084 
00085     OpenNIFeaturePersistence (float &subsampling_leaf_size,
00086                               double &normal_search_radius,
00087                               std::vector<float> &scales_vector,
00088                               float &alpha,
00089                               const std::string& device_id = "")
00090       : viewer ("PCL OpenNI Feature Persistence Viewer")
00091     , device_id_(device_id)
00092     {
00093       std::cout << "Launching with parameters:\n"
00094                 << "    octree_leaf_size = " << subsampling_leaf_size << "\n"
00095                 << "    normal_search_radius = " << normal_search_radius << "\n"
00096                 << "    persistence_alpha = " << alpha << "\n"
00097                 << "    scales = "; for (size_t i = 0; i < scales_vector.size (); ++i) std::cout << scales_vector[i] << " ";
00098       std::cout << "\n";
00099 
00100       subsampling_filter_.setLeafSize (subsampling_leaf_size, subsampling_leaf_size, subsampling_leaf_size);
00101       typename pcl::search::KdTree<PointType>::Ptr normal_search_tree (new typename pcl::search::KdTree<PointType>);
00102       normal_estimation_filter_.setSearchMethod (normal_search_tree);
00103       normal_estimation_filter_.setRadiusSearch (normal_search_radius);
00104 
00105       feature_persistence_.setScalesVector (scales_vector);
00106       feature_persistence_.setAlpha (alpha);
00107 
00108       fpfh_estimation_.reset (new typename pcl::FPFHEstimationOMP<PointType, pcl::Normal, pcl::FPFHSignature33> ());
00109       typename pcl::search::KdTree<PointType>::Ptr fpfh_tree (new typename pcl::search::KdTree<PointType> ());
00110       fpfh_estimation_->setSearchMethod (fpfh_tree);
00111       feature_persistence_.setFeatureEstimator (fpfh_estimation_);
00112       feature_persistence_.setDistanceMetric (pcl::CS);
00113 
00114       new_cloud_ = false;
00115     }
00116 
00117 
00118     void
00119     cloud_cb (const CloudConstPtr& cloud)
00120     {
00121       boost::mutex::scoped_lock lock (mtx_);
00122       //lock while we set our cloud;
00123       FPS_CALC ("computation");
00124 
00125       // Create temporary clouds
00126       cloud_subsampled_.reset (new typename pcl::PointCloud<PointType> ());
00127       normals_.reset (new pcl::PointCloud<pcl::Normal> ());
00128       features_.reset (new pcl::PointCloud<pcl::FPFHSignature33> ());
00129       feature_indices_.reset (new std::vector<int> ());
00130       feature_locations_.reset (new typename pcl::PointCloud<PointType> ());
00131 
00132       // Subsample input cloud
00133       subsampling_filter_.setInputCloud (cloud);
00134       subsampling_filter_.filter (*cloud_subsampled_);
00135 
00136       // Estimate normals
00137       normal_estimation_filter_.setInputCloud (cloud_subsampled_);
00138       normal_estimation_filter_.compute (*normals_);
00139 
00140       // Compute persistent features
00141       fpfh_estimation_->setInputCloud (cloud_subsampled_);
00142       fpfh_estimation_->setInputNormals (normals_);
00143       feature_persistence_.determinePersistentFeatures (*features_, feature_indices_);
00144 
00145       // Extract feature locations by using indices
00146       extract_indices_filter_.setInputCloud (cloud_subsampled_);
00147       extract_indices_filter_.setIndices (feature_indices_);
00148       extract_indices_filter_.filter (*feature_locations_);
00149 
00150       PCL_INFO ("Persistent feature locations %d\n", feature_locations_->points.size ());
00151 
00152       cloud_ = cloud;
00153 
00154       new_cloud_ = true;
00155     }
00156 
00157     void
00158     viz_cb (pcl::visualization::PCLVisualizer& viz)
00159     {
00160       boost::mutex::scoped_lock lock (mtx_);
00161       if (!cloud_)
00162       {
00163         boost::this_thread::sleep(boost::posix_time::seconds(1));
00164         return;
00165       }
00166 
00167       CloudConstPtr temp_cloud;
00168       temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00169 
00170 //      if (!viz.updatePointCloud (temp_cloud, "OpenNICloud"))
00171 //      {
00172 //        viz.addPointCloud (temp_cloud, "OpenNICloud");
00173 //        viz.resetCameraViewpoint ("OpenNICloud");
00174 //      }
00175       // Render the data
00176       if (new_cloud_ && feature_locations_)
00177       {
00178         viz.removePointCloud ("featurecloud");
00179         viz.removePointCloud ("OpenNICloud");
00180         colors_.reset (new typename pcl::visualization::PointCloudColorHandlerCustom<PointType> (feature_locations_, 255.0, 0.0, 0.0));
00181         viz.addPointCloud (feature_locations_, *colors_, "featurecloud");
00182         viz.addPointCloud (temp_cloud, "OpenNICloud");
00183         new_cloud_ = false;
00184       }
00185     }
00186 
00187     void
00188     run ()
00189     {
00190       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00191 
00192       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIFeaturePersistence::cloud_cb, this, _1);
00193       boost::signals2::connection c = interface->registerCallback (f);
00194 
00195       viewer.runOnVisualizationThread (boost::bind(&OpenNIFeaturePersistence::viz_cb, this, _1), "viz_cb");
00196 
00197       interface->start ();
00198 
00199       while (!viewer.wasStopped ())
00200       {
00201         boost::this_thread::sleep(boost::posix_time::seconds(1));
00202       }
00203 
00204       interface->stop ();
00205     }
00206 
00207 
00208     pcl::VoxelGrid<PointType> subsampling_filter_;
00209     pcl::NormalEstimationOMP<PointType, pcl::Normal> normal_estimation_filter_;
00210     typename pcl::FPFHEstimationOMP<PointType, pcl::Normal, pcl::FPFHSignature33>::Ptr fpfh_estimation_;
00211     pcl::MultiscaleFeaturePersistence<PointType, pcl::FPFHSignature33> feature_persistence_;
00212     pcl::ExtractIndices<PointType> extract_indices_filter_;
00213 
00214     pcl::visualization::CloudViewer viewer;
00215     std::string device_id_;
00216     boost::mutex mtx_;
00217     // Data
00218     CloudPtr feature_locations_, cloud_subsampled_;
00219     pcl::PointCloud<pcl::Normal>::Ptr normals_;
00220     pcl::PointCloud<pcl::FPFHSignature33>::Ptr features_;
00221     typename pcl::visualization::PointCloudColorHandlerCustom<PointType>::Ptr colors_;
00222     pcl::IndicesPtr feature_indices_;
00223     CloudConstPtr cloud_;
00224     bool new_cloud_;
00225 };
00226 
00227 void
00228 usage (char ** argv)
00229 {
00230   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00231             << "where options are:\n"
00232             << "         -octree_leaf_size X = size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n"
00233             << "         -normal_search_radius X = size of the neighborhood to consider for calculating the local plane and extracting the normals (default: " << default_normal_search_radius << "\n"
00234             << "         -persistence_alpha X = value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n"
00235             << "         -scales X1 X2 ... = values for the multiple scales for extracting features (default: ";
00236   for (size_t i = 0; i < default_scales_vector.size (); ++i) std::cout << default_scales_vector[i] << " ";
00237   std::cout << "\n\n";
00238 
00239   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00240   if (driver.getNumberDevices () > 0)
00241   {
00242     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00243     {
00244       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00245               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00246       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00247            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00248            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00249     }
00250   }
00251   else
00252     cout << "No devices connected." << endl;
00253 }
00254 
00255 int
00256 main (int argc, char **argv)
00257 {
00258   std::cout << "OpenNIFeaturePersistence - show persistent features based on the MultiscaleFeaturePersistence class using the FPFH features\n"
00259             << "Use \"-h\" to get more info about the available options.\n";
00260 
00261   if (pcl::console::find_argument (argc, argv, "-h") == -1)
00262   {
00263     usage (argv);
00264     return 1;
00265   }
00266 
00267   // Parse arguments
00268   float subsampling_leaf_size = default_subsampling_leaf_size;
00269   pcl::console::parse_argument (argc, argv, "-octree_leaf_size", subsampling_leaf_size);
00270   double normal_search_radius = default_normal_search_radius;
00271   pcl::console::parse_argument (argc, argv, "-normal_search_radius", normal_search_radius);
00272   std::vector<double> scales_vector_double = default_scales_vector;
00273   pcl::console::parse_multiple_arguments (argc, argv, "-scales", scales_vector_double);
00274   std::vector<float> scales_vector (scales_vector_double.size ());
00275   for (size_t i = 0; i < scales_vector_double.size (); ++i) scales_vector[i] = float (scales_vector_double[i]);
00276 
00277   float alpha = default_alpha;
00278   pcl::console::parse_argument (argc, argv, "-persistence_alpha", alpha);
00279 
00280 
00281   pcl::OpenNIGrabber grabber ("");
00282   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00283   {
00284     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00285     OpenNIFeaturePersistence<pcl::PointXYZRGBA> v (subsampling_leaf_size,
00286                                                    normal_search_radius,
00287                                                    scales_vector,
00288                                                    alpha,
00289                                                    "");
00290     v.run ();
00291   }
00292   else
00293   {
00294     PCL_INFO ("PointXYZ mode enabled.\n");
00295     OpenNIFeaturePersistence<pcl::PointXYZ> v (subsampling_leaf_size,
00296                                                normal_search_radius,
00297                                                scales_vector,
00298                                                alpha,
00299                                                "");
00300     v.run ();
00301   }
00302 
00303   return (0);
00304 }
00305 


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