openni_viewer_simple.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 template <typename PointType>
00083 class SimpleOpenNIViewer
00084 {
00085   public:
00086     typedef pcl::PointCloud<PointType> Cloud;
00087     typedef typename Cloud::ConstPtr CloudConstPtr;
00088 
00089     SimpleOpenNIViewer (pcl::OpenNIGrabber& grabber)
00090       : cloud_viewer_ ("PCL OpenNI Viewer")
00091       , grabber_ (grabber)
00092 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00093       , image_viewer_ ("PCL image viewer")
00094 #endif
00095     {
00096     }
00097 
00098     void
00099     cloud_callback (const CloudConstPtr& cloud)
00100     {
00101       FPS_CALC ("cloud callback");
00102       boost::mutex::scoped_lock lock (cloud_mutex_);
00103       cloud_ = cloud;
00104     }
00105 
00106 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00107     void
00108     image_callback (const boost::shared_ptr<openni_wrapper::Image>& image)
00109     {
00110       FPS_CALC ("image callback");
00111       boost::mutex::scoped_lock lock (image_mutex_);
00112       image_ = image;
00113     }
00114     
00115     boost::shared_ptr<openni_wrapper::Image>
00116     getLatestImage ()
00117     {
00118       boost::mutex::scoped_lock lock(image_mutex_);
00119       boost::shared_ptr<openni_wrapper::Image> temp_image;
00120       temp_image.swap (image_);
00121       return (temp_image);
00122     }    
00123 #endif
00124     
00125     void 
00126     keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
00127     {
00128       string* message = (string*)cookie;
00129       cout << (*message) << " :: ";
00130       if (event.getKeyCode())
00131         cout << "the key \'" << event.getKeyCode() << "\' (" << (int)event.getKeyCode() << ") was";
00132       else
00133         cout << "the special key \'" << event.getKeySym() << "\' was";
00134       if (event.keyDown())
00135         cout << " pressed" << endl;
00136       else
00137         cout << " released" << endl;
00138     }
00139     
00140     void mouse_callback (const pcl::visualization::MouseEvent& mouse_event, void* cookie)
00141     {
00142       string* message = (string*) cookie;
00143       if (mouse_event.getType() == pcl::visualization::MouseEvent::MouseButtonPress && mouse_event.getButton() == pcl::visualization::MouseEvent::LeftButton)
00144       {
00145         cout << (*message) << " :: " << mouse_event.getX () << " , " << mouse_event.getY () << endl;
00146       }
00147     }
00152     CloudConstPtr
00153     getLatestCloud ()
00154     {
00155       //lock while we swap our cloud and reset it.
00156       boost::mutex::scoped_lock lock(cloud_mutex_);
00157       CloudConstPtr temp_cloud;
00158       temp_cloud.swap (cloud_); //here we set cloud_ to null, so that
00159       //it is safe to set it again from our
00160       //callback
00161       return (temp_cloud);
00162     }
00163 
00167     void
00168     run ()
00169     {
00170       //pcl::Grabber* interface = new pcl::OpenNIGrabber(device_id_, pcl::OpenNIGrabber::OpenNI_QQVGA_30Hz, pcl::OpenNIGrabber::OpenNI_VGA_30Hz);
00171 
00172       string mouseMsg3D("Mouse coordinates in PCL Visualizer");
00173       string keyMsg3D("Key event for PCL Visualizer");
00174       cloud_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg3D));    
00175       cloud_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg3D));
00176       boost::function<void (const CloudConstPtr&) > cloud_cb = boost::bind (&SimpleOpenNIViewer::cloud_callback, this, _1);
00177       boost::signals2::connection cloud_connection = grabber_.registerCallback (cloud_cb);
00178       
00179 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))
00180       boost::signals2::connection image_connection;
00181       if (grabber_.providesCallback<void (const boost::shared_ptr<openni_wrapper::Image>&)>())
00182       {
00183           string mouseMsg2D("Mouse coordinates in image viewer");
00184           string keyMsg2D("Key event for image viewer");
00185           image_viewer_.registerMouseCallback (&SimpleOpenNIViewer::mouse_callback, *this, (void*)(&mouseMsg2D));
00186           image_viewer_.registerKeyboardCallback(&SimpleOpenNIViewer::keyboard_callback, *this, (void*)(&keyMsg2D));
00187           boost::function<void (const boost::shared_ptr<openni_wrapper::Image>&) > image_cb = boost::bind (&SimpleOpenNIViewer::image_callback, this, _1);
00188           image_connection = grabber_.registerCallback (image_cb);
00189       }
00190       unsigned char* rgb_data = 0;
00191       unsigned rgb_data_size = 0;
00192 #endif        
00193       
00194       grabber_.start ();
00195       
00196       while (!cloud_viewer_.wasStopped(1))
00197       {
00198         if (cloud_)
00199         {
00200           FPS_CALC ("drawing cloud");
00201           //the call to get() sets the cloud_ to null;
00202           cloud_viewer_.showCloud (getLatestCloud ());
00203         }
00204 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))        
00205         if (image_)
00206         {
00207           boost::shared_ptr<openni_wrapper::Image> image = getLatestImage ();
00208 
00209           if (image->getEncoding() == openni_wrapper::Image::RGB)
00210           {
00211             image_viewer_.showRGBImage(image->getMetaData().Data(), image->getWidth(), image->getHeight());
00212           }
00213           else
00214           {
00215             if (rgb_data_size < image->getWidth() * image->getHeight())
00216             {
00217               rgb_data_size = image->getWidth() * image->getHeight();
00218               rgb_data = new unsigned char [rgb_data_size * 3];
00219             }
00220             image->fillRGB (image->getWidth(), image->getHeight(), rgb_data);
00221             image_viewer_.showRGBImage(rgb_data, image->getWidth(), image->getHeight());
00222           }
00223           // This will crash: image_viewer_.spinOnce (10);
00224         }
00225 #endif        
00226         std::cout << __LINE__ << std::endl;
00227       }
00228 
00229       std::cout << __LINE__ << std::endl;
00230       grabber_.stop();
00231       
00232       cloud_connection.disconnect();
00233 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))      
00234       image_connection.disconnect();
00235       if (rgb_data)
00236         delete[] rgb_data;
00237 #endif      
00238     }
00239 
00240     pcl::visualization::CloudViewer cloud_viewer_;
00241     pcl::OpenNIGrabber& grabber_;
00242     boost::mutex cloud_mutex_;
00243     CloudConstPtr cloud_;
00244     
00245 #if !((VTK_MAJOR_VERSION == 5)&&(VTK_MINOR_VERSION <= 4))    
00246     boost::mutex image_mutex_;
00247     boost::shared_ptr<openni_wrapper::Image> image_;
00248     pcl::visualization::ImageViewer image_viewer_;
00249 #endif    
00250 };
00251 
00252 void
00253 usage(char ** argv)
00254 {
00255   cout << "usage: " << argv[0] << " [((<device_id> | <path-to-oni-file>) [-depthmode <mode>] [-imagemode <mode>] [-xyz] | -l [<device_id>]| -h | --help)]" << endl;
00256   cout << argv[0] << " -h | --help : shows this help" << endl;
00257   cout << argv[0] << " -l : list all available devices" << endl;
00258   cout << argv[0] << " -l <device-id> : list all available modes for specified device" << endl;
00259 
00260   cout << "                 device_id may be #1, #2, ... for the first, second etc device in the list"
00261 #ifndef _WIN32
00262        << " or" << endl
00263        << "                 bus@address for the device connected to a specific usb-bus / address combination or" << endl
00264        << "                 <serial-number>"
00265 #endif
00266        << endl;
00267   cout << endl;
00268   cout << "examples:" << endl;
00269   cout << argv[0] << " \"#1\"" << endl;
00270   cout << "    uses the first device." << endl;
00271   cout << argv[0] << " \"./temp/test.oni\"" << endl;
00272   cout << "    uses the oni-player device to play back oni file given by path." << endl;
00273   cout << argv[0] << " -l" << endl;
00274   cout << "    lists all available devices." << endl;
00275   cout << argv[0] << " -l \"#2\"" << endl;
00276   cout << "    lists all available modes for the second device" << endl;
00277   #ifndef _WIN32
00278   cout << argv[0] << " A00361800903049A" << endl;
00279   cout << "    uses the device with the serial number \'A00361800903049A\'." << endl;
00280   cout << argv[0] << " 1@16" << endl;
00281   cout << "    uses the device on address 16 at USB bus 1." << endl;
00282   #endif
00283   return;
00284 }
00285 
00286 int
00287 main(int argc, char ** argv)
00288 {
00289   std::string device_id("");
00290   pcl::OpenNIGrabber::Mode depth_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00291   pcl::OpenNIGrabber::Mode image_mode = pcl::OpenNIGrabber::OpenNI_Default_Mode;
00292   bool xyz = false;
00293   
00294   if (argc >= 2)
00295   {
00296     device_id = argv[1];
00297     if (device_id == "--help" || device_id == "-h")
00298     {
00299       usage(argv);
00300       return 0;
00301     }
00302     else if (device_id == "-l")
00303     {
00304       if (argc >= 3)
00305       {
00306         pcl::OpenNIGrabber grabber(argv[2]);
00307         boost::shared_ptr<openni_wrapper::OpenNIDevice> device = grabber.getDevice();
00308         cout << "Supported depth modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00309         std::vector<std::pair<int, XnMapOutputMode > > modes = grabber.getAvailableDepthModes();
00310         for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00311         {
00312           cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00313         }
00314 
00315         if (device->hasImageStream ())
00316         {
00317           cout << endl << "Supported image modes for device: " << device->getVendorName() << " , " << device->getProductName() << endl;
00318           modes = grabber.getAvailableImageModes();
00319           for (std::vector<std::pair<int, XnMapOutputMode > >::const_iterator it = modes.begin(); it != modes.end(); ++it)
00320           {
00321             cout << it->first << " = " << it->second.nXRes << " x " << it->second.nYRes << " @ " << it->second.nFPS << endl;
00322           }
00323         }
00324       }
00325       else
00326       {
00327         openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00328         if (driver.getNumberDevices() > 0)
00329         {
00330           for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx)
00331           {
00332             cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName(deviceIdx) << ", product: " << driver.getProductName(deviceIdx)
00333               << ", connected: " << (int) driver.getBus(deviceIdx) << " @ " << (int) driver.getAddress(deviceIdx) << ", serial number: \'" << driver.getSerialNumber(deviceIdx) << "\'" << endl;
00334           }
00335 
00336         }
00337         else
00338           cout << "No devices connected." << endl;
00339         
00340         cout <<"Virtual Devices available: ONI player" << endl;
00341       }
00342       return 0;
00343     }
00344   }
00345   else
00346   {
00347     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
00348     if (driver.getNumberDevices() > 0)
00349       cout << "Device Id not set, using first device." << endl;
00350   }
00351   
00352   unsigned mode;
00353   if (pcl::console::parse(argc, argv, "-depthmode", mode) != -1)
00354     depth_mode = (pcl::OpenNIGrabber::Mode) mode;
00355 
00356   if (pcl::console::parse(argc, argv, "-imagemode", mode) != -1)
00357     image_mode = (pcl::OpenNIGrabber::Mode) mode;
00358   
00359   if (pcl::console::find_argument(argc, argv, "-xyz") != -1)
00360     xyz = true;
00361   
00362   pcl::OpenNIGrabber grabber (device_id, depth_mode, image_mode);
00363   
00364   if (xyz) // only if xyz flag is set, since grabber provides at least XYZ and XYZI pointclouds
00365   {
00366     SimpleOpenNIViewer<pcl::PointXYZ> v (grabber);
00367     v.run ();
00368   }
00369   else if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb> ())
00370   {
00371     SimpleOpenNIViewer<pcl::PointXYZRGBA> v (grabber);
00372     v.run ();
00373   }
00374   else
00375   {
00376     SimpleOpenNIViewer<pcl::PointXYZI> v (grabber);
00377     v.run ();
00378   }
00379 
00380   return (0);
00381 }


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