openni_fast_mesh.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 <pcl/point_cloud.h>
00037 #include <pcl/point_types.h>
00038 #include <pcl/io/openni_grabber.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/io/openni_camera/openni_driver.h>
00041 #include <pcl/surface/organized_fast_mesh.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/common/time.h>
00044 #include <pcl/console/time.h>
00045 #include <pcl/visualization/cloud_viewer.h>
00046 
00047 using namespace pcl;
00048 using namespace pcl::visualization;
00049 using namespace std;
00050 
00051 #define FPS_CALC(_WHAT_) \
00052 do \
00053 { \
00054     static unsigned count = 0;\
00055     static double last = pcl::getTime ();\
00056     if (++count == 100) \
00057     { \
00058       double now = pcl::getTime (); \
00059       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00060       count = 0; \
00061       last = now; \
00062     } \
00063 }while(false)
00064 
00065 template <typename PointType>
00066 class OpenNIFastMesh
00067 {
00068   public:
00069     typedef pcl::PointCloud<PointType> Cloud;
00070     typedef typename Cloud::Ptr CloudPtr;
00071     typedef typename Cloud::ConstPtr CloudConstPtr;
00072 
00073     OpenNIFastMesh (const std::string& device_id = "")
00074       : device_id_(device_id), vertices_ ()
00075     {
00076       ofm.setTrianglePixelSize (3);
00077       ofm.setTriangulationType (pcl::OrganizedFastMesh<PointType>::QUAD_MESH);
00078     }
00079     
00080     void 
00081     cloud_cb (const CloudConstPtr& cloud)
00082     {
00083       // Computation goes here
00084       FPS_CALC ("computation");
00085      
00086       // Prepare input
00087       ofm.setInputCloud (cloud);
00088 
00089       // Store the results in a temporary object
00090       boost::shared_ptr<std::vector<pcl::Vertices> > temp_verts (new std::vector<pcl::Vertices>);
00091       ofm.reconstruct (*temp_verts);
00092 
00093       // Lock and copy
00094       {
00095         boost::mutex::scoped_lock lock (mtx_);
00096         //boost::unique_lock<boost::shared_mutex> lock (mtx_);
00097 
00098 //        if (!vertices_)
00099 //          vertices_.reset (new std::vector<pcl::Vertices>);
00100         //vertices_.reset (new std::vector<pcl::Vertices> (*temp_verts));
00101         vertices_= temp_verts;
00102         cloud_ = cloud;//reset (new Cloud (*cloud));
00103       }
00104     }
00105 
00106     void
00107     run (int argc, char **argv)
00108     {
00109       pcl::Grabber* interface = new pcl::OpenNIGrabber (device_id_);
00110 
00111       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIFastMesh::cloud_cb, this, _1);
00112       boost::signals2::connection c = interface->registerCallback (f);
00113      
00114       view.reset (new pcl::visualization::PCLVisualizer (argc, argv, "PCL OpenNI Mesh Viewer"));
00115 
00116       interface->start ();
00117       
00118       CloudConstPtr temp_cloud;
00119       boost::shared_ptr<std::vector<pcl::Vertices> > temp_verts;
00120       pcl::console::TicToc t1;
00121 
00122       while (!view->wasStopped ())
00123       //while (!viewer.wasStopped ())
00124       {
00125         //boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00126         if (!cloud_ || !mtx_.try_lock ())
00127         {
00128           boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00129           continue;
00130         }
00131 
00132         //temp_cloud.reset (new Cloud (*cloud_));
00133         //temp_cloud.swap (cloud_);
00134         //temp_verts.swap (vertices_);//reset (new std::vector<pcl::Vertices> (*vertices_));
00135         temp_cloud = cloud_;
00136         temp_verts = vertices_;//reset (new std::vector<pcl::Vertices> (*vertices_));
00137         mtx_.unlock ();
00138 
00139         //view->removePolygonMesh ("surface");
00140         if (!view->updatePolygonMesh<PointType> (temp_cloud, *temp_verts, "surface"))
00141         {
00142           view->addPolygonMesh<PointType> (temp_cloud, *temp_verts, "surface");
00143           view->resetCameraViewpoint ("surface");
00144         }
00145 
00146         FPS_CALC ("visualization");
00147         view->spinOnce (1);
00148       }
00149 
00150       interface->stop ();
00151     }
00152 
00153     pcl::OrganizedFastMesh<PointType> ofm;
00154     std::string device_id_;
00155     //boost::shared_mutex mtx_;
00156     boost::mutex mtx_;
00157     // Data
00158     CloudConstPtr cloud_;
00159     boost::shared_ptr<std::vector<pcl::Vertices> > vertices_;
00160     pcl::PolygonMesh::Ptr mesh_;
00161 
00162     boost::shared_ptr<pcl::visualization::PCLVisualizer> view;
00163 };
00164 
00165 void
00166 usage (char ** argv)
00167 {
00168   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00169 
00170   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00171   if (driver.getNumberDevices () > 0)
00172   {
00173     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00174     {
00175       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00176               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00177       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00178            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00179            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00180     }
00181   }
00182   else
00183     cout << "No devices connected." << endl;
00184 }
00185 
00186 int
00187 main (int argc, char ** argv)
00188 {
00189   std::string arg;
00190   if (argc > 1)
00191     arg = std::string (argv[1]);
00192   
00193   if (arg == "--help" || arg == "-h")
00194   {
00195     usage (argv);
00196     return 1;
00197   }
00198 
00199   pcl::OpenNIGrabber grabber ("");
00200   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00201   {
00202     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00203     OpenNIFastMesh<pcl::PointXYZRGBA> v ("");
00204     v.run (argc, argv);
00205   }
00206   else
00207   {
00208     PCL_INFO ("PointXYZ mode enabled.\n");
00209     OpenNIFastMesh<pcl::PointXYZ> v ("");
00210     v.run (argc, argv);
00211   }
00212   return (0);
00213 }


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