openni_image.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  *         Radu Bogdan Rusu (rusu@willowgarage.com)
00036  *         Suat Gedikli (gedikli@willowgarage.com)
00037  *         Ethan Rublee (rublee@willowgarage.com)
00038  */
00039 
00040 #include <boost/thread/thread.hpp>
00041 #include <boost/date_time/posix_time/posix_time.hpp>
00042 #include <pcl/point_cloud.h>
00043 #include <pcl/point_types.h>
00044 #include <pcl/common/time.h> //fps calculations
00045 #include <pcl/io/openni_grabber.h>
00046 #include <pcl/visualization/cloud_viewer.h>
00047 #include <pcl/visualization/image_viewer.h>
00048 #include <pcl/io/openni_camera/openni_driver.h>
00049 #include <pcl/console/parse.h>
00050 #include <pcl/visualization/mouse_event.h>
00051 #include <vtkImageViewer.h>
00052 #include <vtkImageImport.h>
00053 #include <vector>
00054 #include <string>
00055 
00056 using namespace std;
00057 
00058 #define SHOW_FPS 1
00059 #if SHOW_FPS
00060 #define FPS_CALC(_WHAT_) \
00061 do \
00062 { \
00063     static unsigned count = 0;\
00064     static double last = pcl::getTime ();\
00065     double now = pcl::getTime (); \
00066     ++count; \
00067     if (now - last >= 1.0) \
00068     { \
00069       std::cout << "Average framerate("<< _WHAT_ << "): " << double(count)/double(now - last) << " Hz" <<  std::endl; \
00070       count = 0; \
00071       last = now; \
00072     } \
00073 }while(false)
00074 #else
00075 #define FPS_CALC(_WHAT_) \
00076 do \
00077 { \
00078 }while(false)
00079 #endif
00080 
00082 class SimpleOpenNIViewer
00083 {
00084   public:
00085     SimpleOpenNIViewer (pcl::OpenNIGrabber& grabber)
00086       : grabber_ (grabber),
00087         image_viewer_ ("PCL/OpenNI RGB image viewer"),
00088         depth_image_viewer_ ("PCL/OpenNI depth image viewer"),
00089         image_cld_init_ (false), depth_image_cld_init_ (false)
00090     {
00091     }
00092 
00093     void
00094     image_callback (const boost::shared_ptr<openni_wrapper::Image> &image, 
00095                     const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image, float)
00096     {
00097       FPS_CALC ("image callback");
00098       boost::mutex::scoped_lock lock (image_mutex_);
00099       image_ = image;
00100       depth_image_ = depth_image;
00101     }
00102     
00103     void 
00104     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
00105     {
00106       string* message = static_cast<string*> (cookie);
00107       cout << (*message) << " :: ";
00108       if (event.getKeyCode ())
00109         cout << "the key \'" << event.getKeyCode () << "\' (" << event.getKeyCode () << ") was";
00110       else
00111         cout << "the special key \'" << event.getKeySym () << "\' was";
00112       if (event.keyDown ())
00113         cout << " pressed" << endl;
00114       else
00115         cout << " released" << endl;
00116     }
00117     
00118     void 
00119     mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
00120     {
00121       string* message = static_cast<string*> (cookie);
00122       if (mouse_event.getType () == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton () == pcl::visualization::MouseEvent::LeftButton)
00123       {
00124         cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
00125       }
00126     }
00127 
00128     void
00129     run ()
00130     {
00131       string mouseMsg2D ("Mouse coordinates in image viewer");
00132       string keyMsg2D ("Key event for image viewer");
00133 
00134       image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, static_cast<void*> (&mouseMsg2D));
00135       image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, static_cast<void*> (&keyMsg2D));
00136       depth_image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, static_cast<void*> (&mouseMsg2D));
00137       depth_image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, static_cast<void*> (&keyMsg2D));
00138         
00139       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);
00140       boost::signals2::connection image_connection = grabber_.registerCallback (image_cb);
00141       
00142       grabber_.start ();
00143       
00144       unsigned char* rgb_data = 0;
00145       unsigned rgb_data_size = 0;
00146       
00147       while (!image_viewer_.wasStopped () && !depth_image_viewer_.wasStopped ())
00148       {
00149         boost::mutex::scoped_lock lock (image_mutex_);
00150         if (image_)
00151         {
00152           boost::shared_ptr<openni_wrapper::Image> image;
00153           image.swap (image_);
00154 
00155           if (!image_cld_init_)
00156           {
00157             image_viewer_.setPosition (0, 0);
00158             image_cld_init_ = !image_cld_init_;
00159           }
00160 
00161           if (image->getEncoding() == openni_wrapper::Image::RGB)
00162             image_viewer_.showRGBImage (image->getMetaData ().Data (), image->getWidth (), image->getHeight ());
00163           else
00164           {
00165             if (rgb_data_size < image->getWidth () * image->getHeight ())
00166             {
00167               if (rgb_data)
00168                 delete [] rgb_data;
00169               rgb_data_size = image->getWidth () * image->getHeight ();
00170               rgb_data = new unsigned char [rgb_data_size * 3];
00171             }
00172             image->fillRGB (image->getWidth (), image->getHeight (), rgb_data);
00173             image_viewer_.showRGBImage (rgb_data, image->getWidth (), image->getHeight ());
00174           }
00175         }
00176         if (depth_image_)
00177         {
00178           boost::shared_ptr<openni_wrapper::DepthImage> depth_image;
00179           depth_image.swap (depth_image_);
00180 
00181           if (!depth_image_cld_init_)
00182           {
00183             depth_image_viewer_.setPosition (depth_image->getWidth (), 0);
00184             depth_image_cld_init_ = !depth_image_cld_init_;
00185           }
00186 
00187           depth_image_viewer_.showShortImage (reinterpret_cast<const unsigned short*> (depth_image->getDepthMetaData ().Data ()), 
00188                                               depth_image->getWidth (), depth_image->getHeight (),
00189                                               std::numeric_limits<unsigned short>::min (), 
00190                                               // Scale so that the colors look brigher on screen
00191                                               std::numeric_limits<unsigned short>::max () / 10, 
00192                                               true);
00193         }
00194         image_viewer_.spinOnce ();
00195         depth_image_viewer_.spinOnce ();
00196       }
00197 
00198       grabber_.stop ();
00199       
00200       image_connection.disconnect ();
00201       
00202       if (rgb_data)
00203         delete[] rgb_data;
00204     }
00205 
00206     pcl::OpenNIGrabber& grabber_;
00207     boost::mutex image_mutex_;
00208     boost::shared_ptr<openni_wrapper::Image> image_;
00209     boost::shared_ptr<openni_wrapper::DepthImage> depth_image_;
00210     pcl::visualization::ImageViewer image_viewer_;
00211     pcl::visualization::ImageViewer depth_image_viewer_;
00212     bool image_cld_init_, depth_image_cld_init_;
00213 };
00214 
00215 void
00216 usage (char ** argv)
00217 {
00218   cout << "usage: " << argv[0] << " [((<device_id> | <path-to-oni-file>) [-imagemode <mode>] | -l [<device_id>]| -h | --help)]" << endl;
00219   cout << argv[0] << " -h | --help : shows this help" << endl;
00220   cout << argv[0] << " -l : list all available devices" << endl;
00221   cout << argv[0] << " -l <device-id> : list all available modes for specified device" << endl;
00222 
00223   cout << "                 device_id may be #1, #2, ... for the first, second etc device in the list"
00224 #ifndef _WIN32
00225        << " or" << endl
00226        << "                 bus@address for the device connected to a specific usb-bus / address combination or" << endl
00227        << "                 <serial-number>"
00228 #endif
00229        << endl;
00230   cout << endl;
00231   cout << "examples:" << endl;
00232   cout << argv[0] << " \"#1\"" << endl;
00233   cout << "    uses the first device." << endl;
00234   cout << argv[0] << " \"./temp/test.oni\"" << endl;
00235   cout << "    uses the oni-player device to play back oni file given by path." << endl;
00236   cout << argv[0] << " -l" << endl;
00237   cout << "    lists all available devices." << endl;
00238   cout << argv[0] << " -l \"#2\"" << endl;
00239   cout << "    lists all available modes for the second device" << endl;
00240 #ifndef _WIN32
00241   cout << argv[0] << " A00361800903049A" << endl;
00242   cout << "    uses the device with the serial number \'A00361800903049A\'." << endl;
00243   cout << argv[0] << " 1@16" << endl;
00244   cout << "    uses the device on address 16 at USB bus 1." << endl;
00245 #endif
00246 }
00247 
00248 int
00249 main (int argc, char ** argv)
00250 {
00251   std::string device_id ("");
00252   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00253   
00254   if (argc >= 2)
00255   {
00256     device_id = argv[1];
00257     if (device_id == "--help" || device_id == "-h")
00258     {
00259       usage (argv);
00260       return (0);
00261     }
00262     else if (device_id == "-l")
00263     {
00264       if (argc >= 3)
00265       {
00266         pcl::OpenNIGrabber grabber (argv[2]);
00267         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice ();
00268         std::vector<std::pair<int, XnMapOutputMode> > modes;
00269 
00270         if (device->hasImageStream ())
00271         {
00272           cout << endl << "Supported image modes for device: " << device->getVendorName () << " , " << device->getProductName () << endl;
00273           modes = grabber.getAvailableImageModes ();
00274           for (std::vector<std::pair<int, XnMapOutputMode> >::const_iterator it = modes.begin (); it != modes.end (); ++it)
00275           {
00276             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00277           }
00278         }
00279       }
00280       else
00281       {
00282         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00283         if (driver.getNumberDevices () > 0)
00284         {
00285           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices (); ++deviceIdx)
00286           {
00287             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
00288               << ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << endl;
00289           }
00290 
00291         }
00292         else
00293           cout << "No devices connected." << endl;
00294         
00295         cout <<"Virtual Devices available: ONI player" << endl;
00296       }
00297       return (0);
00298     }
00299   }
00300   else
00301   {
00302     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00303     if (driver.getNumberDevices() > 0)
00304       cout << "Device Id not set, using first device." << endl;
00305   }
00306   
00307   unsigned mode;
00308   if (pcl::console::parse (argc, argv, "-imagemode", mode) != -1)
00309     image_mode = static_cast<pcl::OpenNIGrabber::Mode> (mode);
00310   
00311   pcl::OpenNIGrabber grabber (device_id, pcl::OpenNIGrabber::OpenNI_Default_Mode, image_mode);
00312   SimpleOpenNIViewer v (grabber);
00313   v.run ();
00314 
00315   return (0);
00316 }


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