openni_grab_images.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  * Author: Nico Blodow (blodow@cs.tum.edu)
00035  *         Christian Potthast (potthast@usc.edu)
00036  */
00037 
00038 #include <pcl/point_types.h>
00039 #include <pcl/io/openni_grabber.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/common/time.h>
00042 #include <pcl/console/print.h>
00043 #include <pcl/console/parse.h>
00044 #include <boost/filesystem.hpp>
00045 #include <pcl/visualization/vtk.h>
00046 #include <pcl/visualization/image_viewer.h>
00047 #include <pcl/visualization/common/float_image_utils.h>
00048 
00049 using namespace pcl::console;
00050 using namespace boost::filesystem;
00051 
00052 class OpenNIGrabFrame
00053 {
00054   public:
00055     OpenNIGrabFrame (pcl::OpenNIGrabber& grabber, bool paused) 
00056     : grabber_ (grabber)
00057     , image_viewer_ ("RGB Image")
00058     , depth_image_viewer_ ("Depth Image")
00059     , quit_ (false)
00060     , continuous_ (!paused)
00061     , trigger_ (false)
00062     , importer_ (vtkSmartPointer<vtkImageImport>::New ())
00063     , depth_importer_ (vtkSmartPointer<vtkImageImport>::New ())
00064     , writer_ (vtkSmartPointer<vtkTIFFWriter>::New ())
00065     , flipper_ (vtkSmartPointer<vtkImageFlip>::New ())    
00066     {
00067       importer_->SetNumberOfScalarComponents (3);
00068       importer_->SetDataScalarTypeToUnsignedChar ();
00069       depth_importer_->SetNumberOfScalarComponents (1);
00070       depth_importer_->SetDataScalarTypeToUnsignedShort ();
00071       writer_->SetCompressionToPackBits ();
00072       flipper_->SetFilteredAxes (1);      
00073     }
00074 
00075     void
00076     image_callback (const boost::shared_ptr<openni_wrapper::Image> &image, 
00077                     const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image, float)
00078     {
00079       boost::mutex::scoped_lock lock (image_mutex_);
00080       image_ = image;
00081       depth_image_ = depth_image;
00082       lock.unlock ();
00083     }
00084     
00085     void 
00086     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void*)
00087     {
00088       if (event.keyUp ())
00089       {
00090         switch (event.getKeyCode ())
00091         {
00092           case 27:
00093           case 'Q':
00094           case 'q': quit_ = true;
00095             break;
00096           case ' ': continuous_ = !continuous_;
00097             break;
00098           case 'G':
00099           case 'g': trigger_ = true;
00100             break;
00101         }
00102       }
00103     }
00104     
00105     void 
00106     mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void*)
00107     {
00108       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00109       {
00110         trigger_ = true;
00111       }
00112     }
00113     
00114     void saveImages ()
00115     {
00116       std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ());
00117       boost::shared_ptr<openni_wrapper::Image> image;
00118       boost::shared_ptr<openni_wrapper::DepthImage> depth_image;
00119 
00120       image_mutex_.lock ();
00121       image.swap (image_);
00122       depth_image.swap (depth_image_);
00123       image_mutex_.unlock ();
00124 
00125       static unsigned char* rgb_data = 0;
00126       static unsigned rgb_data_size = 0;
00127       
00128       if (image)
00129       {
00130         const void* data;
00131         if (image->getEncoding() != openni_wrapper::Image::RGB)
00132         {
00133           if (rgb_data_size < image->getWidth () * image->getHeight ())
00134           {
00135             if (rgb_data)
00136               delete [] rgb_data;
00137             rgb_data_size = image->getWidth () * image->getHeight ();
00138             rgb_data = new unsigned char [rgb_data_size * 3];
00139           }
00140           image->fillRGB (image->getWidth (), image->getHeight (), rgb_data);
00141           data = reinterpret_cast<const void*> (rgb_data);
00142         }
00143         else
00144           data = reinterpret_cast<const void*> (image->getMetaData ().Data ());
00145 
00146         importer_->SetWholeExtent (0, image->getWidth () - 1, 0, image->getHeight () - 1, 0, 0);
00147         importer_->SetDataExtentToWholeExtent ();
00148         
00149         std::stringstream ss;
00150         ss << "frame_" + time + "_rgb.tiff";
00151         importer_->SetImportVoidPointer (const_cast<void*>(data), 1);
00152         importer_->Update ();
00153         flipper_->SetInputConnection (importer_->GetOutputPort ());
00154         flipper_->Update ();
00155         writer_->SetFileName (ss.str ().c_str ());
00156         writer_->SetInputConnection (flipper_->GetOutputPort ());
00157         writer_->Write ();     
00158       }
00159       if (depth_image)
00160       {
00161         std::stringstream ss;
00162         ss << "frame_" + time + "_depth.tiff";
00163 
00164         depth_importer_->SetWholeExtent (0, depth_image->getWidth () - 1, 0, depth_image->getHeight () - 1, 0, 0);
00165         depth_importer_->SetDataExtentToWholeExtent ();
00166         depth_importer_->SetImportVoidPointer (const_cast<void*> (reinterpret_cast<const void*> (depth_image->getDepthMetaData ().Data ())), 1);
00167         depth_importer_->Update ();
00168         flipper_->SetInputConnection (depth_importer_->GetOutputPort ());
00169         flipper_->Update ();
00170         writer_->SetFileName (ss.str ().c_str ());
00171         writer_->SetInputConnection (flipper_->GetOutputPort ());
00172         writer_->Write ();
00173       }
00174 
00175       trigger_ = false;
00176     }
00177     
00178     int 
00179     run ()
00180     {
00181       // register the keyboard and mouse callback for the visualizer
00182       image_viewer_.registerMouseCallback (&OpenNIGrabFrame::mouse_callback, *this);
00183       image_viewer_.registerKeyboardCallback(&OpenNIGrabFrame::keyboard_callback, *this);
00184       depth_image_viewer_.registerMouseCallback (&OpenNIGrabFrame::mouse_callback, *this);
00185       depth_image_viewer_.registerKeyboardCallback(&OpenNIGrabFrame::keyboard_callback, *this);
00186       
00187       boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float) > image_cb = boost::bind (&OpenNIGrabFrame::image_callback, this, _1, _2, _3);
00188       boost::signals2::connection image_connection = grabber_.registerCallback (image_cb);
00189       
00190       // start receiving point clouds
00191       grabber_.start ();
00192       unsigned char* rgb_data = 0;
00193       unsigned rgb_data_size = 0;
00194       unsigned char* depth_data = 0;
00195 
00196       // wait until user quits program with Ctrl-C, but no busy-waiting -> sleep (1);
00197       while (!image_viewer_.wasStopped() && !quit_)
00198       {
00199         std::string time = boost::posix_time::to_iso_string (boost::posix_time::microsec_clock::local_time ());
00200         boost::shared_ptr<openni_wrapper::Image> image;
00201         boost::shared_ptr<openni_wrapper::DepthImage> depth_image;
00202         
00203         if (image_mutex_.try_lock ())
00204         {
00205           image.swap (image_);
00206           depth_image.swap (depth_image_);
00207           image_mutex_.unlock ();
00208         }
00209         
00210         if (image)
00211         {
00212           const void* data;
00213           if (image->getEncoding() != openni_wrapper::Image::RGB)
00214           {
00215             if (rgb_data_size < image->getWidth () * image->getHeight ())
00216             {
00217               if (rgb_data)
00218                 delete [] rgb_data;
00219               rgb_data_size = image->getWidth () * image->getHeight ();
00220               rgb_data = new unsigned char [rgb_data_size * 3];
00221             }
00222             image->fillRGB (image->getWidth (), image->getHeight (), rgb_data);
00223             data = reinterpret_cast<const void*> (rgb_data);
00224           }
00225           else
00226             data = reinterpret_cast<const void*> (image->getMetaData ().Data ());            
00227           image_viewer_.addRGBImage ((const unsigned char*) data, image->getWidth (), image->getHeight ());
00228           
00229           if (continuous_ || trigger_)
00230           {
00231             importer_->SetWholeExtent (0, image->getWidth () - 1, 0, image->getHeight () - 1, 0, 0);
00232             importer_->SetDataExtentToWholeExtent ();
00233 
00234             std::stringstream ss;
00235             ss << "frame_" + time + "_rgb.tiff";
00236             importer_->SetImportVoidPointer (const_cast<void*>(data), 1);
00237             importer_->Update ();
00238             flipper_->SetInputConnection (importer_->GetOutputPort ());
00239             flipper_->Update ();
00240             writer_->SetFileName (ss.str ().c_str ());
00241             writer_->SetInputConnection (flipper_->GetOutputPort ());
00242             writer_->Write ();
00243             cout << "writing rgb frame: " << ss.str () << endl;
00244           }
00245         } // if (image_)
00246         
00247         
00248         if (depth_image)
00249         {
00250           if (depth_data)
00251             delete[] depth_data;
00252           depth_data = pcl::visualization::FloatImageUtils::getVisualImage (
00253               reinterpret_cast<const unsigned short*> (depth_image->getDepthMetaData ().Data ()),
00254                 depth_image->getWidth (), depth_image->getHeight (),
00255                 std::numeric_limits<unsigned short>::min (), 
00256                 // Scale so that the colors look brigher on screen
00257                 std::numeric_limits<unsigned short>::max () / 10, 
00258                 true);
00259           
00260           depth_image_viewer_.addRGBImage (depth_data, depth_image->getWidth (), depth_image->getHeight ());
00261           if (continuous_ || trigger_)
00262           {
00263             std::stringstream ss;
00264             ss << "frame_" + time + "_depth.tiff";
00265 
00266             depth_importer_->SetWholeExtent (0, depth_image->getWidth () - 1, 0, depth_image->getHeight () - 1, 0, 0);
00267             depth_importer_->SetDataExtentToWholeExtent ();
00268             depth_importer_->SetImportVoidPointer (const_cast<void*> (reinterpret_cast<const void*> (depth_image->getDepthMetaData ().Data ())), 1);
00269             depth_importer_->Update ();
00270             flipper_->SetInputConnection (depth_importer_->GetOutputPort ());
00271             flipper_->Update ();
00272             writer_->SetFileName (ss.str ().c_str ());
00273             writer_->SetInputConnection (flipper_->GetOutputPort ());
00274             writer_->Write ();
00275             cout << "writing depth frame: " << ss.str () << endl;
00276           }
00277         }
00278         trigger_ = false;
00279         image_viewer_.spinOnce ();
00280         depth_image_viewer_.spinOnce ();
00281         //boost::this_thread::sleep (boost::posix_time::microseconds (100));
00282       }
00283       
00284       image_mutex_.lock ();
00285       // stop the grabber
00286       grabber_.stop ();
00287       image_mutex_.unlock ();
00288       return 0;
00289     }
00290 
00291     pcl::OpenNIGrabber& grabber_;
00292     pcl::visualization::ImageViewer image_viewer_;
00293     pcl::visualization::ImageViewer depth_image_viewer_;
00294     bool quit_;
00295     bool continuous_;
00296     bool trigger_;
00297     mutable boost::mutex image_mutex_;
00298     boost::shared_ptr<openni_wrapper::Image> image_;
00299     boost::shared_ptr<openni_wrapper::DepthImage> depth_image_;
00300     vtkSmartPointer<vtkImageImport> importer_, depth_importer_;
00301     vtkSmartPointer<vtkTIFFWriter> writer_;
00302     vtkSmartPointer<vtkImageFlip> flipper_;
00303 };
00304 
00305 void
00306 usage (char ** argv)
00307 {
00308   cout << "usage: " << argv[0] << " [((<device_id> | <path-to-oni-file>) [-imagemode <mode>] [-depthformat <format>] [-paused] | -l [<device_id>]| -h | --help)]" << endl;
00309   cout << argv[0] << " -h | --help : shows this help" << endl;
00310   cout << argv[0] << " -l : list all available devices" << endl;
00311   cout << argv[0] << " -l <device-id> : list all available modes for specified device" << endl;
00312 
00313   cout << "                 device_id may be #1, #2, ... for the first, second etc device in the list"
00314 #ifndef _WIN32
00315        << " or" << endl
00316        << "                 bus@address for the device connected to a specific usb-bus / address combination or" << endl
00317        << "                 <serial-number>"
00318 #endif
00319        << endl;
00320   cout << "                 -paused : start grabber in paused mode. Toggle pause by pressing the space bar\n";
00321   cout << "                           or grab single frames by just pressing the left mouse button.\n";
00322   cout << endl;
00323   cout << "examples:" << endl;
00324   cout << argv[0] << " \"#1\"" << endl;
00325   cout << "    uses the first device." << endl;
00326   cout << argv[0] << " \"./temp/test.oni\"" << endl;
00327   cout << "    uses the oni-player device to play back oni file given by path." << endl;
00328   cout << argv[0] << " -l" << endl;
00329   cout << "    lists all available devices." << endl;
00330   cout << argv[0] << " -l \"#2\"" << endl;
00331   cout << "    lists all available modes for the second device" << endl;
00332 #ifndef _WIN32
00333   cout << argv[0] << " A00361800903049A" << endl;
00334   cout << "    uses the device with the serial number \'A00361800903049A\'." << endl;
00335   cout << argv[0] << " 1@16" << endl;
00336   cout << "    uses the device on address 16 at USB bus 1." << endl;
00337 #endif  
00338 }
00339 
00340 int 
00341 main (int argc, char** argv)
00342 {
00343   std::string device_id ("");
00344   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00345   
00346   if (argc >= 2)
00347   {
00348     device_id = argv[1];
00349     if (device_id == "--help" || device_id == "-h")
00350     {
00351       usage (argv);
00352       return (0);
00353     }
00354     else if (device_id == "-l")
00355     {
00356       if (argc >= 3)
00357       {
00358         pcl::OpenNIGrabber grabber (argv[2]);
00359         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice ();
00360         std::vector<std::pair<int, XnMapOutputMode> > modes;
00361 
00362         if (device->hasImageStream ())
00363         {
00364           cout << endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << endl;
00365           modes = grabber.getAvailableImageModes ();
00366           for (std::vector<std::pair<int, XnMapOutputMode> >::const_iterator it = modes.begin (); it != modes.end (); ++it)
00367           {
00368             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00369           }
00370         }
00371       }
00372       else
00373       {
00374         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00375         if (driver.getNumberDevices () > 0)
00376         {
00377           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00378           {
00379             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00380               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00381           }
00382 
00383         }
00384         else
00385           cout << "No devices connected." << endl;
00386         
00387         cout <<"Virtual Devices available: ONI player" << endl;
00388       }
00389       return (0);
00390     }
00391   }
00392   else
00393   {
00394     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00395     if (driver.getNumberDevices() > 0)
00396       cout << "Device Id not set, using first device." << endl;
00397   }
00398   
00399   unsigned mode;
00400   if (pcl::console::parse (argc, argv, "-imagemode", mode) != -1)
00401     image_mode = static_cast<pcl::OpenNIGrabber::Mode> (mode);
00402   
00403   int depthformat = openni_wrapper::OpenNIDevice::OpenNI_12_bit_depth;
00404   pcl::console::parse_argument (argc, argv, "-depthformat", depthformat);
00405 
00406   pcl::OpenNIGrabber grabber (device_id, pcl::OpenNIGrabber::OpenNI_Default_Mode, image_mode);
00407   // Set the depth output format
00408   grabber.getDevice ()->setDepthOutputFormat (static_cast<openni_wrapper::OpenNIDevice::DepthMode> (depthformat));
00409 
00410   bool paused = find_switch (argc, argv, "-paused");
00411   
00412   OpenNIGrabFrame grabFrame (grabber, paused);
00413   return grabFrame.run ();
00414 }
00415 


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