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 <pcl/point_cloud.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/openni_grabber.h>
00041 #include <pcl/io/pcd_io.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/visualization/cloud_viewer.h>
00046 
00047 #include <pcl/features/multiscale_feature_persistence.h>
00048 #include <pcl/features/fpfh_omp.h>
00049 #include <pcl/filters/voxel_grid.h>
00050 #include <pcl/filters/extract_indices.h>
00051 #include <pcl/features/normal_3d_omp.h>
00052 
00053 
00054 #define FPS_CALC(_WHAT_) \
00055 do \
00056 { \
00057     static unsigned count = 0;\
00058     static double last = pcl::getTime ();\
00059     double now = pcl::getTime (); \
00060     ++count; \
00061     if (now - last >= 1.0) \
00062     { \
00063       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00064       count = 0; \
00065       last = now; \
00066     } \
00067 }while(false)
00068 
00069 const float default_subsampling_leaf_size = 0.02f;
00070 const float default_normal_search_radius = 0.041f;
00071 const double aux [] = {0.21, 0.32};
00072 const std::vector<double> default_scales_vector (aux, aux + 2);
00073 const float default_alpha = 1.2f;
00074 
00075 template <typename PointType>
00076 class OpenNIFeaturePersistence
00077 {
00078   public:
00079     typedef pcl::PointCloud<PointType> Cloud;
00080     typedef typename Cloud::Ptr CloudPtr;
00081     typedef typename Cloud::ConstPtr CloudConstPtr;
00082 
00083     OpenNIFeaturePersistence (float &subsampling_leaf_size,
00084                               double &normal_search_radius,
00085                               std::vector<float> &scales_vector,
00086                               float &alpha,
00087                               const std::string& device_id = "")
00088       : viewer ("PCL OpenNI Feature Persistence Viewer")
00089     , device_id_(device_id)
00090     {
00091       std::cout << "Launching with parameters:\n"
00092                 << "    octree_leaf_size = " << subsampling_leaf_size << "\n"
00093                 << "    normal_search_radius = " << normal_search_radius << "\n"
00094                 << "    persistence_alpha = " << alpha << "\n"
00095                 << "    scales = "; for (size_t i = 0; i < scales_vector.size (); ++i) std::cout << scales_vector[i] << " ";
00096       std::cout << "\n";
00097 
00098       subsampling_filter_.setLeafSize (subsampling_leaf_size, subsampling_leaf_size, subsampling_leaf_size);
00099       typename pcl::search::KdTree<PointType>::Ptr normal_search_tree (new typename pcl::search::KdTree<PointType>);
00100       normal_estimation_filter_.setSearchMethod (normal_search_tree);
00101       normal_estimation_filter_.setRadiusSearch (normal_search_radius);
00102 
00103       feature_persistence_.setScalesVector (scales_vector);
00104       feature_persistence_.setAlpha (alpha);
00105 
00106       fpfh_estimation_.reset (new typename pcl::FPFHEstimationOMP<PointType, pcl::Normal, pcl::FPFHSignature33> ());
00107       typename pcl::search::KdTree<PointType>::Ptr fpfh_tree (new typename pcl::search::KdTree<PointType> ());
00108       fpfh_estimation_->setSearchMethod (fpfh_tree);
00109       feature_persistence_.setFeatureEstimator (fpfh_estimation_);
00110       feature_persistence_.setDistanceMetric (pcl::CS);
00111 
00112       new_cloud_ = false;
00113     }
00114 
00115 
00116     void
00117     cloud_cb (const CloudConstPtr& cloud)
00118     {
00119       boost::mutex::scoped_lock lock (mtx_);
00120       //lock while we set our cloud;
00121       FPS_CALC ("computation");
00122 
00123       // Create temporary clouds
00124       cloud_subsampled_.reset (new typename pcl::PointCloud<PointType> ());
00125       normals_.reset (new pcl::PointCloud<pcl::Normal> ());
00126       features_.reset (new pcl::PointCloud<pcl::FPFHSignature33> ());
00127       feature_indices_.reset (new std::vector<int> ());
00128       feature_locations_.reset (new typename pcl::PointCloud<PointType> ());
00129 
00130       // Subsample input cloud
00131       subsampling_filter_.setInputCloud (cloud);
00132       subsampling_filter_.filter (*cloud_subsampled_);
00133 
00134       // Estimate normals
00135       normal_estimation_filter_.setInputCloud (cloud_subsampled_);
00136       normal_estimation_filter_.compute (*normals_);
00137 
00138       // Compute persistent features
00139       fpfh_estimation_->setInputCloud (cloud_subsampled_);
00140       fpfh_estimation_->setInputNormals (normals_);
00141       feature_persistence_.determinePersistentFeatures (*features_, feature_indices_);
00142 
00143       // Extract feature locations by using indices
00144       extract_indices_filter_.setInputCloud (cloud_subsampled_);
00145       extract_indices_filter_.setIndices (feature_indices_);
00146       extract_indices_filter_.filter (*feature_locations_);
00147 
00148       PCL_INFO ("Persistent feature locations %d\n", feature_locations_->points.size ());
00149 
00150       cloud_ = cloud;
00151 
00152       new_cloud_ = true;
00153     }
00154 
00155     void
00156     viz_cb (pcl::visualization::PCLVisualizer& viz)
00157     {
00158       boost::mutex::scoped_lock lock (mtx_);
00159       if (!cloud_)
00160       {
00161         boost::this_thread::sleep(boost::posix_time::seconds(1));
00162         return;
00163       }
00164 
00165       CloudConstPtr temp_cloud;
00166       temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00167 
00168 //      if (!viz.updatePointCloud (temp_cloud, "OpenNICloud"))
00169 //      {
00170 //        viz.addPointCloud (temp_cloud, "OpenNICloud");
00171 //        viz.resetCameraViewpoint ("OpenNICloud");
00172 //      }
00173       // Render the data
00174       if (new_cloud_ && feature_locations_)
00175       {
00176         viz.removePointCloud ("featurecloud");
00177         viz.removePointCloud ("OpenNICloud");
00178         colors_.reset (new typename pcl::visualization::PointCloudColorHandlerCustom<PointType> (feature_locations_, 255.0, 0.0, 0.0));
00179         viz.addPointCloud (feature_locations_, *colors_, "featurecloud");
00180         viz.addPointCloud (temp_cloud, "OpenNICloud");
00181         new_cloud_ = false;
00182       }
00183     }
00184 
00185     void
00186     run ()
00187     {
00188       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00189 
00190       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIFeaturePersistence::cloud_cb, this, _1);
00191       boost::signals2::connection c = interface->registerCallback (f);
00192 
00193       viewer.runOnVisualizationThread (boost::bind(&OpenNIFeaturePersistence::viz_cb, this, _1), "viz_cb");
00194 
00195       interface->start ();
00196 
00197       while (!viewer.wasStopped ())
00198       {
00199         boost::this_thread::sleep(boost::posix_time::seconds(1));
00200       }
00201 
00202       interface->stop ();
00203     }
00204 
00205 
00206     pcl::VoxelGrid<PointType> subsampling_filter_;
00207     pcl::NormalEstimationOMP<PointType, pcl::Normal> normal_estimation_filter_;
00208     typename pcl::FPFHEstimationOMP<PointType, pcl::Normal, pcl::FPFHSignature33>::Ptr fpfh_estimation_;
00209     pcl::MultiscaleFeaturePersistence<PointType, pcl::FPFHSignature33> feature_persistence_;
00210     pcl::ExtractIndices<PointType> extract_indices_filter_;
00211 
00212     pcl::visualization::CloudViewer viewer;
00213     std::string device_id_;
00214     boost::mutex mtx_;
00215     // Data
00216     CloudPtr feature_locations_, cloud_subsampled_;
00217     pcl::PointCloud<pcl::Normal>::Ptr normals_;
00218     pcl::PointCloud<pcl::FPFHSignature33>::Ptr features_;
00219     typename pcl::visualization::PointCloudColorHandlerCustom<PointType>::Ptr colors_;
00220     pcl::IndicesPtr feature_indices_;
00221     CloudConstPtr cloud_;
00222     bool new_cloud_;
00223 };
00224 
00225 void
00226 usage (char ** argv)
00227 {
00228   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n"
00229             << "where options are:\n"
00230             << "         -octree_leaf_size X = size of the leaf for the octree-based subsampling filter (default: " << default_subsampling_leaf_size << "\n"
00231             << "         -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"
00232             << "         -persistence_alpha X = value of alpha for the multiscale feature persistence (default: " << default_alpha << "\n"
00233             << "         -scales X1 X2 ... = values for the multiple scales for extracting features (default: ";
00234   for (size_t i = 0; i < default_scales_vector.size (); ++i) std::cout << default_scales_vector[i] << " ";
00235   std::cout << "\n\n";
00236 
00237   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00238   if (driver.getNumberDevices () > 0)
00239   {
00240     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00241     {
00242       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00243               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00244       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00245            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00246            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00247     }
00248   }
00249   else
00250     cout << "No devices connected." << endl;
00251 }
00252 
00253 int
00254 main (int argc, char **argv)
00255 {
00256   std::cout << "OpenNIFeaturePersistence - show persistent features based on the MultiscaleFeaturePersistence class using the FPFH features\n"
00257             << "Use \"-h\" to get more info about the available options.\n";
00258 
00259   if (pcl::console::find_argument (argc, argv, "-h") == -1)
00260   {
00261     usage (argv);
00262     return 1;
00263   }
00264 
00265   // Parse arguments
00266   float subsampling_leaf_size = default_subsampling_leaf_size;
00267   pcl::console::parse_argument (argc, argv, "-octree_leaf_size", subsampling_leaf_size);
00268   double normal_search_radius = default_normal_search_radius;
00269   pcl::console::parse_argument (argc, argv, "-normal_search_radius", normal_search_radius);
00270   std::vector<double> scales_vector_double = default_scales_vector;
00271   pcl::console::parse_multiple_arguments (argc, argv, "-scales", scales_vector_double);
00272   std::vector<float> scales_vector (scales_vector_double.size ());
00273   for (size_t i = 0; i < scales_vector_double.size (); ++i) scales_vector[i] = float (scales_vector_double[i]);
00274 
00275   float alpha = default_alpha;
00276   pcl::console::parse_argument (argc, argv, "-persistence_alpha", alpha);
00277 
00278 
00279   pcl::OpenNIGrabber grabber ("");
00280   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00281   {
00282     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00283     OpenNIFeaturePersistence<pcl::PointXYZRGBA> v (subsampling_leaf_size,
00284                                                    normal_search_radius,
00285                                                    scales_vector,
00286                                                    alpha,
00287                                                    "");
00288     v.run ();
00289   }
00290   else
00291   {
00292     PCL_INFO ("PointXYZ mode enabled.\n");
00293     OpenNIFeaturePersistence<pcl::PointXYZ> v (subsampling_leaf_size,
00294                                                normal_search_radius,
00295                                                scales_vector,
00296                                                alpha,
00297                                                "");
00298     v.run ();
00299   }
00300 
00301   return (0);
00302 }
00303 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:26:25