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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:59