openni_boundary_estimation.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/filters/approximate_voxel_grid.h>
00044 #include <pcl/features/boundary.h>
00045 #include <pcl/features/integral_image_normal.h>
00046 #include <pcl/console/parse.h>
00047 #include <pcl/common/time.h>
00048 #include <pcl/visualization/cloud_viewer.h>
00049 
00050 typedef pcl::visualization::PointCloudColorHandler<pcl::PCLPointCloud2> ColorHandler;
00051 typedef ColorHandler::Ptr ColorHandlerPtr;
00052 typedef ColorHandler::ConstPtr ColorHandlerConstPtr;
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 class OpenNIIntegralImageNormalEstimation
00070 {
00071   public:
00072     typedef pcl::PointCloud<pcl::PointXYZRGBNormal> Cloud;
00073     typedef Cloud::Ptr CloudPtr;
00074     typedef Cloud::ConstPtr CloudConstPtr;
00075 
00076     OpenNIIntegralImageNormalEstimation (const std::string& device_id = "")
00077       : viewer ("PCL OpenNI NormalEstimation Viewer") 
00078     , device_id_(device_id)
00079     {
00080       ne_.setNormalEstimationMethod (ne_.AVERAGE_3D_GRADIENT);
00081       //ne_.setNormalEstimationMethod (ne_.COVARIANCE_MATRIX);
00082       ne_.setRectSize (10, 10);
00083       new_cloud_ = false;
00084 
00085       pass_.setDownsampleAllData (true);
00086       pass_.setLeafSize (0.005f, 0.005f, 0.005f);
00087 
00088       pcl::search::OrganizedNeighbor<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::OrganizedNeighbor<pcl::PointXYZRGBNormal>);
00089       be_.setRadiusSearch (0.02);
00090       be_.setSearchMethod (tree);
00091     }
00092     
00093     void 
00094     cloud_cb (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud)
00095     {
00096       boost::mutex::scoped_lock lock (mtx_);
00097       //lock while we set our cloud;
00098       FPS_CALC ("computation");
00099 
00100       cloud_.reset (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00101 
00102       // Estimate surface normals
00103       ne_.setInputCloud (cloud);
00104       ne_.compute (*cloud_);
00105       copyPointCloud (*cloud, *cloud_);
00106 
00107 //      cloud_pass_.reset (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00108       // Passthrough
00109 //      pass_.setInputCloud (cloud_);
00110 //      pass_.filter (*cloud_pass_);
00111 
00112       be_.setInputCloud (cloud_);
00113       be_.setInputNormals (cloud_);
00114       boundaries_.reset (new pcl::PointCloud<pcl::Boundary>);
00115       be_.compute (*boundaries_);
00116 
00117       new_cloud_ = true;
00118     }
00119 
00120     void
00121     viz_cb (pcl::visualization::PCLVisualizer& viz)
00122     {
00123       boost::mutex::scoped_lock lock (mtx_);
00124       if (!cloud_)
00125       {
00126         boost::this_thread::sleep(boost::posix_time::seconds(1));
00127         return;
00128       }
00129 
00130       // Render the data 
00131       if (new_cloud_ && cloud_ && boundaries_)
00132       {
00133         CloudPtr temp_cloud;
00134         temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00135 
00136 //        if (!viz.updatePointCloud<pcl::PointXYZRGBNormal> (temp_cloud, "OpenNICloud"))
00137 //        {
00138 //          viz.addPointCloud<pcl::PointXYZRGBNormal> (temp_cloud, "OpenNICloud");
00139 //          viz.resetCameraViewpoint ("OpenNICloud");
00140 //        }
00141 
00142         viz.removePointCloud ("normalcloud");
00143         pcl::PCLPointCloud2::Ptr cloud2 (new pcl::PCLPointCloud2);
00144         pcl::toPCLPointCloud2 (*boundaries_, *cloud2);
00145         ColorHandlerConstPtr color_handler (new pcl::visualization::PointCloudColorHandlerGenericField<pcl::PCLPointCloud2> (cloud2, "boundary_point"));
00146         viz.addPointCloud<pcl::PointXYZRGBNormal> (temp_cloud, color_handler, "normalcloud");
00147         viz.resetCameraViewpoint ("normalcloud");
00148         new_cloud_ = false;
00149       }
00150     }
00151 
00152     void
00153     run ()
00154     {
00155       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00156 
00157       boost::function<void (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr &)> f = boost::bind (&OpenNIIntegralImageNormalEstimation::cloud_cb, this, _1);
00158       boost::signals2::connection c = interface->registerCallback (f);
00159      
00160       viewer.runOnVisualizationThread (boost::bind(&OpenNIIntegralImageNormalEstimation::viz_cb, this, _1), "viz_cb");
00161 
00162       interface->start ();
00163       
00164       while (!viewer.wasStopped ())
00165       {
00166         boost::this_thread::sleep(boost::posix_time::seconds(1));
00167       }
00168 
00169       interface->stop ();
00170     }
00171 
00172     pcl::ApproximateVoxelGrid<pcl::PointXYZRGBNormal> pass_;
00173     pcl::IntegralImageNormalEstimation<pcl::PointXYZRGB, pcl::PointXYZRGBNormal> ne_;
00174     pcl::BoundaryEstimation<pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal, pcl::Boundary> be_;
00175     pcl::visualization::CloudViewer viewer;
00176     std::string device_id_;
00177     boost::mutex mtx_;
00178     // Data
00179     pcl::PointCloud<pcl::Boundary>::Ptr boundaries_;
00180     CloudPtr cloud_, cloud_pass_;
00181     bool new_cloud_;
00182 };
00183 
00184 void
00185 usage (char ** argv)
00186 {
00187   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00188 
00189   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00190   if (driver.getNumberDevices () > 0)
00191   {
00192     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00193     {
00194       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00195               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00196       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00197            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00198            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00199     }
00200   }
00201   else
00202     cout << "No devices connected." << endl;
00203 }
00204 
00205 int 
00206 main (int argc, char ** argv)
00207 {
00208   std::string arg;
00209   if (argc > 1)
00210     arg = std::string (argv[1]);
00211   
00212   if (arg == "--help" || arg == "-h")
00213   {
00214     usage (argv);
00215     return 1;
00216   }
00217 
00218   pcl::OpenNIGrabber grabber ("");
00219   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb> ())
00220   {
00221     OpenNIIntegralImageNormalEstimation v ("");
00222     v.run ();
00223   }
00224   else
00225     PCL_ERROR ("The input device does not provide a PointXYZRGB mode.\n");
00226 
00227   return (0);
00228 }


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