openni_io.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 <boost/thread/thread.hpp>
00037 #include <boost/date_time/posix_time/posix_time.hpp>
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/console/time.h>
00046 
00047 using namespace pcl;
00048 using namespace std;
00049 
00050 #define FPS_CALC(_WHAT_) \
00051 do \
00052 { \
00053     static unsigned count = 0;\
00054     static double last = pcl::getTime ();\
00055     if (++count == 100) \
00056     { \
00057       double now = pcl::getTime (); \
00058       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00059       count = 0; \
00060       last = now; \
00061     } \
00062 }while(false)
00063 
00064 template <typename PointType>
00065 class OpenNIIO
00066 {
00067   public:
00068     typedef pcl::PointCloud<PointType> Cloud;
00069     typedef typename Cloud::Ptr CloudPtr;
00070     typedef typename Cloud::ConstPtr CloudConstPtr;
00071 
00072     OpenNIIO (const std::string& device_id = "")
00073       : device_id_ (device_id), mtx_ (), cloud_ (), interface_ (), writer_ ()
00074     {
00075     }
00076 
00077     virtual ~OpenNIIO ()
00078     {
00079       if (interface_)
00080         interface_->stop ();
00081     }
00082     
00083     void 
00084     cloud_cb (const CloudConstPtr& cloud)
00085     {
00086       boost::mutex::scoped_lock lock (mtx_);
00087       FPS_CALC ("callback");
00088 
00089       cloud_ = cloud;
00090     }
00091 
00092     void
00093     init ()
00094     {
00095       interface_ = new pcl::OpenNIGrabber (device_id_);
00096 
00097       boost::function<void (const CloudConstPtr&)> f = boost::bind (&OpenNIIO::cloud_cb, this, _1);
00098       boost::signals2::connection c = interface_->registerCallback (f);
00099      
00100       interface_->start ();
00101       
00102       writer_.setMapSynchronization (false);    // Setting this to true will enable msync() => drop I/O performance
00103     }
00104 
00105     void
00106     run ()
00107     {
00108       while (true)
00109       {
00110         if (cloud_)
00111         {
00112           //boost::mutex::scoped_lock lock (mtx_);
00113           FPS_CALC ("write");
00114 
00115           CloudConstPtr temp_cloud;
00116           temp_cloud.swap (cloud_);
00117           writer_.writeBinaryCompressed ("test_binary.pcd", *temp_cloud);
00118         }
00119         boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00120       }
00121     }
00122 
00123     void
00124     runEigen ()
00125     {
00126       while (true)
00127       {
00128         if (cloud_)
00129         {
00130           //boost::mutex::scoped_lock lock (mtx_);
00131           FPS_CALC ("write");
00132 
00133           CloudConstPtr temp_cloud;
00134           temp_cloud.swap (cloud_);
00135           writer_.writeBinaryCompressedEigen ("test_binary.pcd", *temp_cloud);
00136         }
00137         boost::this_thread::sleep (boost::posix_time::milliseconds (1));
00138       }
00139     }
00140 
00141     std::string device_id_;
00142     boost::mutex mtx_;
00143     CloudConstPtr cloud_;
00144     pcl::Grabber* interface_;
00145     PCDWriter writer_;
00146 };
00147 
00148 void
00149 usage (char ** argv)
00150 {
00151   std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
00152 
00153   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00154   if (driver.getNumberDevices () > 0)
00155   {
00156     for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00157     {
00158       cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00159               << ", connected: " << static_cast<int> (driver.getBus (deviceIdx)) << " @ " << static_cast<int> (driver.getAddress (deviceIdx)) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00160       cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << endl
00161            << "                 bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << endl
00162            << "                 <serial-number> (only in Linux and for devices which provide serial numbers)"  << endl;
00163     }
00164   }
00165   else
00166     cout << "No devices connected." << endl;
00167 }
00168 
00169 int
00170 main (int argc, char ** argv)
00171 {
00172   std::string arg;
00173   if (argc > 1)
00174     arg = std::string (argv[1]);
00175   
00176   if (arg == "--help" || arg == "-h")
00177   {
00178     usage (argv);
00179     return 1;
00180   }
00181 
00182   pcl::OpenNIGrabber grabber ("");
00183   if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_eigen> ())
00184   {
00185     PCL_INFO ("Eigen mode enabled.\n");
00186     OpenNIIO<Eigen::MatrixXf> v ("");
00187     v.init ();
00188     v.runEigen ();
00189   }
00190   else if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba> ())
00191   {
00192     PCL_INFO ("PointXYZRGBA mode enabled.\n");
00193     OpenNIIO<pcl::PointXYZRGBA> v ("");
00194     v.init ();
00195     v.run ();
00196   }
00197   else
00198   {
00199     PCL_INFO ("PointXYZ mode enabled.\n");
00200     OpenNIIO<pcl::PointXYZ> v ("");
00201     v.init ();
00202     v.run ();
00203   }
00204   return (0);
00205 }


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