openni_save_image.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) 2011, 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 the copyright holder(s) 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/common/time.h> //fps calculations
00039 #include <pcl/io/openni_grabber.h>
00040 #include <pcl/io/openni_camera/openni_driver.h>
00041 #include <pcl/console/parse.h>
00042 #include <vector>
00043 #include <string>
00044 
00045 #include <pcl/visualization/vtk.h>
00046 #include <pcl/visualization/pcl_visualizer.h>
00047 #include "boost.h"
00048 
00049 #define SHOW_FPS 1
00050 #if SHOW_FPS
00051 #define FPS_CALC(_WHAT_) \
00052 do \
00053 { \
00054     static unsigned count = 0;\
00055     static double last = pcl::getTime ();\
00056     double now = pcl::getTime (); \
00057     ++count; \
00058     if (now - last >= 1.0) \
00059     { \
00060       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00061       count = 0; \
00062       last = now; \
00063     } \
00064 }while(false)
00065 #else
00066 #define FPS_CALC(_WHAT_) \
00067 do \
00068 { \
00069 }while(false)
00070 #endif
00071 
00073 class SimpleOpenNIViewer
00074 {
00075   public:
00076     SimpleOpenNIViewer (pcl::OpenNIGrabber& grabber)
00077       : grabber_ (grabber)
00078       , image_mutex_ ()
00079       , image_ ()
00080       , depth_image_ ()
00081       , importer_ (vtkSmartPointer<vtkImageImport>::New ())
00082       , depth_importer_ (vtkSmartPointer<vtkImageImport>::New ())
00083       , writer_ (vtkSmartPointer<vtkTIFFWriter>::New ())
00084       , flipper_ (vtkSmartPointer<vtkImageFlip>::New ())
00085     {
00086       importer_->SetNumberOfScalarComponents (3);
00087       importer_->SetDataScalarTypeToUnsignedChar ();
00088       depth_importer_->SetNumberOfScalarComponents (1);
00089       depth_importer_->SetDataScalarTypeToUnsignedShort ();
00090       writer_->SetCompressionToPackBits ();
00091       flipper_->SetFilteredAxes (1);
00092     }
00093 
00094     void
00095     image_callback (const boost::shared_ptr<openni_wrapper::Image> &image, 
00096                     const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image, float)
00097     {
00098       FPS_CALC ("image callback");
00099       boost::mutex::scoped_lock lock (image_mutex_);
00100       image_ = image;
00101       depth_image_ = depth_image;
00102     }
00103     
00104     void
00105     run ()
00106     {
00107       boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float) > image_cb = boost::bind (&SimpleOpenNIViewer::image_callback, this, _1, _2, _3);
00108       boost::signals2::connection image_connection = grabber_.registerCallback (image_cb);
00109       
00110       grabber_.start ();
00111       
00112       unsigned char* rgb_data = 0;
00113       unsigned rgb_data_size = 0;
00114       const void* data;
00115        
00116       while (true)
00117       {
00118         boost::mutex::scoped_lock lock (image_mutex_);
00119 
00120         std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ());
00121         if (image_)
00122         {
00123           FPS_CALC ("writer callback");
00124           boost::shared_ptr<openni_wrapper::Image> image;
00125           image.swap (image_);
00126 
00127           if (image->getEncoding() == openni_wrapper::Image::RGB)
00128           {
00129             data = reinterpret_cast<const void*> (image->getMetaData ().Data ());
00130             importer_->SetWholeExtent (0, image->getWidth () - 1, 0, image->getHeight () - 1, 0, 0);
00131             importer_->SetDataExtentToWholeExtent ();
00132           }
00133           else
00134           {
00135             if (rgb_data_size < image->getWidth () * image->getHeight ())
00136             {
00137               rgb_data_size = image->getWidth () * image->getHeight ();
00138               rgb_data = new unsigned char [rgb_data_size * 3];
00139               importer_->SetWholeExtent (0, image->getWidth () - 1, 0, image->getHeight () - 1, 0, 0);
00140               importer_->SetDataExtentToWholeExtent ();
00141             }
00142             image->fillRGB (image->getWidth (), image->getHeight (), rgb_data);
00143             data = reinterpret_cast<const void*> (rgb_data);
00144           }
00145 
00146           std::stringstream ss;
00147           ss << "frame_" + time + "_rgb.tiff";
00148           importer_->SetImportVoidPointer (const_cast<void*>(data), 1);
00149           importer_->Update ();
00150           flipper_->SetInputConnection (importer_->GetOutputPort ());
00151           flipper_->Update ();
00152           writer_->SetFileName (ss.str ().c_str ());
00153           writer_->SetInputConnection (flipper_->GetOutputPort ());
00154           writer_->Write ();
00155         }
00156 
00157         if (depth_image_)
00158         {
00159           boost::shared_ptr<openni_wrapper::DepthImage> depth_image;
00160           depth_image.swap (depth_image_);
00161 
00162           std::stringstream ss;
00163           ss << "frame_" + time + "_depth.tiff";
00164 
00165           depth_importer_->SetWholeExtent (0, depth_image->getWidth () - 1, 0, depth_image->getHeight () - 1, 0, 0);
00166           depth_importer_->SetDataExtentToWholeExtent ();
00167           depth_importer_->SetImportVoidPointer (const_cast<void*> (reinterpret_cast<const void*> (depth_image->getDepthMetaData ().Data ())), 1);
00168           depth_importer_->Update ();
00169           flipper_->SetInputConnection (depth_importer_->GetOutputPort ());
00170           flipper_->Update ();
00171           writer_->SetFileName (ss.str ().c_str ());
00172           writer_->SetInputConnection (flipper_->GetOutputPort ());
00173           writer_->Write ();
00174         }
00175       }
00176 
00177       grabber_.stop ();
00178       
00179       image_connection.disconnect ();
00180       
00181       if (rgb_data)
00182         delete[] rgb_data;
00183     }
00184 
00185     pcl::OpenNIGrabber& grabber_;
00186     boost::mutex image_mutex_;
00187     boost::shared_ptr<openni_wrapper::Image> image_;
00188     boost::shared_ptr<openni_wrapper::DepthImage> depth_image_;
00189     vtkSmartPointer<vtkImageImport> importer_, depth_importer_;
00190     vtkSmartPointer<vtkTIFFWriter> writer_;
00191     vtkSmartPointer<vtkImageFlip> flipper_;
00192 };
00193 
00194 void
00195 usage (char ** argv)
00196 {
00197   cout << "usage: " << argv[0] << " [((<device_id> | <path-to-oni-file>) [-imagemode <mode>] | -l [<device_id>]| -h | --help)]" << endl;
00198   cout << argv[0] << " -h | --help : shows this help" << endl;
00199   cout << argv[0] << " -l : list all available devices" << endl;
00200   cout << argv[0] << " -l <device-id> : list all available modes for specified device" << endl;
00201 
00202   cout << "                 device_id may be #1, #2, ... for the first, second etc device in the list"
00203 #ifndef _WIN32
00204        << " or" << endl
00205        << "                 bus@address for the device connected to a specific usb-bus / address combination or" << endl
00206        << "                 <serial-number>"
00207 #endif
00208        << endl;
00209   cout << endl;
00210   cout << "examples:" << endl;
00211   cout << argv[0] << " \"#1\"" << endl;
00212   cout << "    uses the first device." << endl;
00213   cout << argv[0] << " \"./temp/test.oni\"" << endl;
00214   cout << "    uses the oni-player device to play back oni file given by path." << endl;
00215   cout << argv[0] << " -l" << endl;
00216   cout << "    lists all available devices." << endl;
00217   cout << argv[0] << " -l \"#2\"" << endl;
00218   cout << "    lists all available modes for the second device" << endl;
00219 #ifndef _WIN32
00220   cout << argv[0] << " A00361800903049A" << endl;
00221   cout << "    uses the device with the serial number \'A00361800903049A\'." << endl;
00222   cout << argv[0] << " 1@16" << endl;
00223   cout << "    uses the device on address 16 at USB bus 1." << endl;
00224 #endif
00225   return;
00226 }
00227 
00228 int
00229 main(int argc, char ** argv)
00230 {
00231   std::string device_id ("");
00232   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00233   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00234   
00235   if (argc >= 2)
00236   {
00237     device_id = argv[1];
00238     if (device_id == "--help" || device_id == "-h")
00239     {
00240       usage(argv);
00241       return 0;
00242     }
00243     else if (device_id == "-l")
00244     {
00245       if (argc >= 3)
00246       {
00247         pcl::OpenNIGrabber grabber (argv[2]);
00248         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice ();
00249         std::vector<std::pair<int, XnMapOutputMode> > modes;
00250 
00251         if (device->hasImageStream ())
00252         {
00253           cout << endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << endl;
00254           modes = grabber.getAvailableImageModes ();
00255           for (std::vector<std::pair<int, XnMapOutputMode> >::const_iterator it = modes.begin (); it != modes.end (); ++it)
00256           {
00257             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00258           }
00259         }
00260       }
00261       else
00262       {
00263         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00264         if (driver.getNumberDevices () > 0)
00265         {
00266           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00267           {
00268             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00269               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00270           }
00271 
00272         }
00273         else
00274           cout << "No devices connected." << endl;
00275         
00276         cout <<"Virtual Devices available: ONI player" << endl;
00277       }
00278       return (0);
00279     }
00280   }
00281   else
00282   {
00283     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00284     if (driver.getNumberDevices () > 0)
00285       cout << "Device Id not set, using first device." << endl;
00286   }
00287   
00288   unsigned imagemode;
00289   if (pcl::console::parse (argc, argv, "-imagemode", imagemode) != -1)
00290     image_mode = pcl::OpenNIGrabber::Mode (imagemode);
00291   unsigned depthmode;
00292   if (pcl::console::parse (argc, argv, "-depthmode", depthmode) != -1)
00293     depth_mode = pcl::OpenNIGrabber::Mode (depthmode);
00294   
00295 
00296   pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode);
00297   SimpleOpenNIViewer v (grabber);
00298   v.run ();
00299 
00300   return (0);
00301 }


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