openni_grabber.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) 2010-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 
00039 #include <pcl/pcl_config.h>
00040 #ifdef HAVE_OPENNI
00041 
00042 #include <pcl/io/openni_grabber.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/common/time.h>
00046 #include <pcl/console/print.h>
00047 #include <pcl/io/boost.h>
00048 #include <pcl/exceptions.h>
00049 #include <iostream>
00050 
00051 namespace pcl
00052 {
00053   typedef union
00054   {
00055     struct
00056     {
00057       unsigned char Blue;
00058       unsigned char Green;
00059       unsigned char Red;
00060       unsigned char Alpha;
00061     };
00062     float float_value;
00063     uint32_t long_value;
00064   } RGBValue;
00065 }
00066 
00068 pcl::OpenNIGrabber::OpenNIGrabber (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
00069   : rgb_sync_ ()
00070   , ir_sync_ ()
00071   , device_ ()
00072   , rgb_frame_id_ ()
00073   , depth_frame_id_ ()
00074   , image_width_ ()
00075   , image_height_ ()
00076   , depth_width_ ()
00077   , depth_height_ ()
00078   , image_required_ (false)
00079   , depth_required_ (false)
00080   , ir_required_ (false)
00081   , sync_required_ (false)
00082   , image_signal_ (), depth_image_signal_ (), ir_image_signal_ (), image_depth_image_signal_ ()
00083   , ir_depth_image_signal_ (), point_cloud_signal_ (), point_cloud_i_signal_ ()
00084   , point_cloud_rgb_signal_ (), point_cloud_rgba_signal_ ()
00085   , config2xn_map_ (), depth_callback_handle (), image_callback_handle (), ir_callback_handle ()
00086   , running_ (false)
00087   , rgb_focal_length_x_ (std::numeric_limits<double>::quiet_NaN ())
00088   , rgb_focal_length_y_ (std::numeric_limits<double>::quiet_NaN ())
00089   , rgb_principal_point_x_ (std::numeric_limits<double>::quiet_NaN ())
00090   , rgb_principal_point_y_ (std::numeric_limits<double>::quiet_NaN ())
00091   , depth_focal_length_x_ (std::numeric_limits<double>::quiet_NaN ())
00092   , depth_focal_length_y_ (std::numeric_limits<double>::quiet_NaN ())
00093   , depth_principal_point_x_ (std::numeric_limits<double>::quiet_NaN ())
00094   , depth_principal_point_y_ (std::numeric_limits<double>::quiet_NaN ())
00095 {
00096   // initialize driver
00097   onInit (device_id, depth_mode, image_mode);
00098 
00099   if (!device_->hasDepthStream ())
00100     PCL_THROW_EXCEPTION (pcl::IOException, "Device does not provide 3D information.");
00101 
00102   depth_image_signal_    = createSignal<sig_cb_openni_depth_image> ();
00103   ir_image_signal_       = createSignal<sig_cb_openni_ir_image> ();
00104   point_cloud_signal_    = createSignal<sig_cb_openni_point_cloud> ();
00105   point_cloud_i_signal_  = createSignal<sig_cb_openni_point_cloud_i> ();
00106   ir_depth_image_signal_ = createSignal<sig_cb_openni_ir_depth_image> ();
00107 
00108   ir_sync_.addCallback (boost::bind (&OpenNIGrabber::irDepthImageCallback, this, _1, _2));
00109   if (device_->hasImageStream ())
00110   {
00111     // create callback signals
00112     image_signal_             = createSignal<sig_cb_openni_image> ();
00113     image_depth_image_signal_ = createSignal<sig_cb_openni_image_depth_image> ();
00114     point_cloud_rgb_signal_   = createSignal<sig_cb_openni_point_cloud_rgb> ();
00115     point_cloud_rgba_signal_  = createSignal<sig_cb_openni_point_cloud_rgba> ();
00116     rgb_sync_.addCallback (boost::bind (&OpenNIGrabber::imageDepthImageCallback, this, _1, _2));
00117     openni_wrapper::DeviceKinect* kinect = dynamic_cast<openni_wrapper::DeviceKinect*> (device_.get ());
00118     if (kinect)
00119       kinect->setDebayeringMethod (openni_wrapper::ImageBayerGRBG::EdgeAware);
00120   }
00121 
00122   image_callback_handle = device_->registerImageCallback (&OpenNIGrabber::imageCallback, *this);
00123   depth_callback_handle = device_->registerDepthCallback (&OpenNIGrabber::depthCallback, *this);
00124   ir_callback_handle    = device_->registerIRCallback (&OpenNIGrabber::irCallback, *this);
00125 }
00126 
00128 pcl::OpenNIGrabber::~OpenNIGrabber () throw ()
00129 {
00130   try
00131   {
00132     stop ();
00133 
00134     // unregister callbacks
00135     device_->unregisterDepthCallback (depth_callback_handle);
00136 
00137     if (device_->hasImageStream ())
00138       device_->unregisterImageCallback (image_callback_handle);
00139 
00140     if (device_->hasIRStream ())
00141       device_->unregisterIRCallback (image_callback_handle);
00142 
00143     // release the pointer to the device object
00144     device_.reset ();
00145     
00146     // disconnect all listeners
00147     disconnect_all_slots<sig_cb_openni_image> ();
00148     disconnect_all_slots<sig_cb_openni_depth_image> ();
00149     disconnect_all_slots<sig_cb_openni_ir_image> ();
00150     disconnect_all_slots<sig_cb_openni_image_depth_image> ();
00151     disconnect_all_slots<sig_cb_openni_point_cloud> ();
00152     disconnect_all_slots<sig_cb_openni_point_cloud_rgb> ();
00153     disconnect_all_slots<sig_cb_openni_point_cloud_rgba> ();
00154     disconnect_all_slots<sig_cb_openni_point_cloud_i> ();
00155 
00156     openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00157     driver.stopAll ();
00158   }
00159   catch (...)
00160   {
00161     // destructor never throws
00162   }
00163 }
00164 
00166 void
00167 pcl::OpenNIGrabber::checkImageAndDepthSynchronizationRequired ()
00168 {
00169   // do we have anyone listening to images or color point clouds?
00170   if (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
00171       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
00172       num_slots<sig_cb_openni_image_depth_image> () > 0)
00173     sync_required_ = true;
00174   else
00175     sync_required_ = false;
00176 }
00177 
00179 void
00180 pcl::OpenNIGrabber::checkImageStreamRequired ()
00181 {
00182   // do we have anyone listening to images or color point clouds?
00183   if (num_slots<sig_cb_openni_image>             () > 0 ||
00184       num_slots<sig_cb_openni_image_depth_image> () > 0 ||
00185       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
00186       num_slots<sig_cb_openni_point_cloud_rgb>   () > 0)
00187     image_required_ = true;
00188   else
00189     image_required_ = false;
00190 }
00191 
00193 void
00194 pcl::OpenNIGrabber::checkDepthStreamRequired ()
00195 {
00196   // do we have anyone listening to depth images or (color) point clouds?
00197   if (num_slots<sig_cb_openni_depth_image>       () > 0 ||
00198       num_slots<sig_cb_openni_image_depth_image> () > 0 ||
00199       num_slots<sig_cb_openni_ir_depth_image>    () > 0 ||
00200       num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
00201       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
00202       num_slots<sig_cb_openni_point_cloud>       () > 0 ||
00203       num_slots<sig_cb_openni_point_cloud_i>     () > 0 )
00204     depth_required_ = true;
00205   else
00206     depth_required_ = false;
00207 }
00208 
00210 void
00211 pcl::OpenNIGrabber::checkIRStreamRequired ()
00212 {
00213   if (num_slots<sig_cb_openni_ir_image>       () > 0 ||
00214       num_slots<sig_cb_openni_point_cloud_i>  () > 0 ||
00215       num_slots<sig_cb_openni_ir_depth_image> () > 0)
00216     ir_required_ = true;
00217   else
00218     ir_required_ = false;
00219 }
00220 
00222 void
00223 pcl::OpenNIGrabber::start ()
00224 {
00225   try
00226   {
00227     // check if we need to start/stop any stream
00228     if (image_required_ && !device_->isImageStreamRunning ())
00229     {
00230       block_signals ();
00231       device_->startImageStream ();
00232       //startSynchronization ();
00233     }
00234 
00235     if (depth_required_ && !device_->isDepthStreamRunning ())
00236     {
00237       block_signals ();
00238       if (device_->hasImageStream () && !device_->isDepthRegistered () && device_->isDepthRegistrationSupported ())
00239       {
00240         device_->setDepthRegistration (true);
00241       }
00242       device_->startDepthStream ();
00243       //startSynchronization ();
00244     }
00245 
00246     if (ir_required_ && !device_->isIRStreamRunning ())
00247     {
00248       block_signals ();
00249       device_->startIRStream ();
00250     }
00251     running_ = true;
00252   }
00253   catch (openni_wrapper::OpenNIException& ex)
00254   {
00255     PCL_THROW_EXCEPTION (pcl::IOException, "Could not start streams. Reason: " << ex.what ());
00256   }
00257   // workaround, since the first frame is corrupted
00258   boost::this_thread::sleep (boost::posix_time::seconds (1));
00259   unblock_signals ();
00260 }
00261 
00263 void
00264 pcl::OpenNIGrabber::stop ()
00265 {
00266   try
00267   {
00268     if (device_->hasDepthStream () && device_->isDepthStreamRunning ())
00269       device_->stopDepthStream ();
00270 
00271     if (device_->hasImageStream () && device_->isImageStreamRunning ())
00272       device_->stopImageStream ();
00273 
00274     if (device_->hasIRStream () && device_->isIRStreamRunning ())
00275       device_->stopIRStream ();
00276 
00277     running_ = false;
00278   }
00279   catch (openni_wrapper::OpenNIException& ex)
00280   {
00281     PCL_THROW_EXCEPTION (pcl::IOException, "Could not stop streams. Reason: " << ex.what ());
00282   }
00283 }
00284 
00286 bool
00287 pcl::OpenNIGrabber::isRunning () const
00288 {
00289   return (running_);
00290 }
00291 
00293 void
00294 pcl::OpenNIGrabber::onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
00295 {
00296   updateModeMaps (); // registering mapping from config modes to XnModes and vice versa
00297   setupDevice (device_id, depth_mode, image_mode);
00298 
00299   rgb_frame_id_ = "/openni_rgb_optical_frame";
00300 
00301   depth_frame_id_ = "/openni_depth_optical_frame";
00302 }
00303 
00305 void
00306 pcl::OpenNIGrabber::signalsChanged ()
00307 {
00308   // reevaluate which streams are required
00309   checkImageStreamRequired ();
00310   checkDepthStreamRequired ();
00311   checkIRStreamRequired ();
00312   if (ir_required_ && image_required_)
00313     PCL_THROW_EXCEPTION (pcl::IOException, "Can not provide IR stream and RGB stream at the same time.");
00314 
00315   checkImageAndDepthSynchronizationRequired ();
00316   if (running_)
00317     start ();
00318 }
00319 
00321 std::string
00322 pcl::OpenNIGrabber::getName () const
00323 {
00324   return std::string ("OpenNIGrabber");
00325 }
00326 
00328 void
00329 pcl::OpenNIGrabber::setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode)
00330 {
00331   // Initialize the openni device
00332   openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance ();
00333 
00334   try
00335   {
00336     if (boost::filesystem::exists (device_id))
00337     {
00338       device_ = driver.createVirtualDevice (device_id, true, true);
00339     }
00340     else if (driver.getNumberDevices () == 0)
00341     {
00342       PCL_THROW_EXCEPTION (pcl::IOException, "No devices connected.");
00343     }
00344     else if (device_id[0] == '#')
00345     {
00346       unsigned index = atoi (device_id.c_str () + 1);
00347       //printf("[%s] searching for device with index = %d\n", getName().c_str(), index);
00348       device_ = driver.getDeviceByIndex (index - 1);
00349     }
00350 #ifndef _WIN32
00351     else if (device_id.find ('@') != std::string::npos)
00352     {
00353       size_t pos = device_id.find ('@');
00354       unsigned bus = atoi (device_id.substr (0, pos).c_str ());
00355       unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
00356       //printf("[%s] searching for device with bus@address = %d@%d\n", getName().c_str(), bus, address);
00357       device_ = driver.getDeviceByAddress (static_cast<unsigned char>(bus), static_cast<unsigned char>(address) );
00358     }
00359 #endif
00360     else if (!device_id.empty ())
00361     {
00362       //printf("[%s] searching for device with serial number = %s\n", getName().c_str(), device_id.c_str());
00363       device_ = driver.getDeviceBySerialNumber (device_id);
00364     }
00365     else
00366     {
00367       device_ = driver.getDeviceByIndex (0);
00368     }
00369   }
00370   catch (const openni_wrapper::OpenNIException& exception)
00371   {
00372     if (!device_)
00373       PCL_THROW_EXCEPTION (pcl::IOException, "No matching device found. " << exception.what ())
00374     else
00375       PCL_THROW_EXCEPTION (pcl::IOException, "could not retrieve device. Reason " << exception.what ())
00376   }
00377   catch (const pcl::IOException&)
00378   {
00379     throw;
00380   }
00381   catch (...)
00382   {
00383     PCL_THROW_EXCEPTION (pcl::IOException, "unknown error occured");
00384   }
00385 
00386   XnMapOutputMode depth_md;
00387   // Set the selected output mode
00388   if (depth_mode != OpenNI_Default_Mode)
00389   {
00390     XnMapOutputMode actual_depth_md;
00391     if (!mapConfigMode2XnMode (depth_mode, depth_md) || !device_->findCompatibleDepthMode (depth_md, actual_depth_md))
00392       PCL_THROW_EXCEPTION (pcl::IOException, "could not find compatible depth stream mode " << static_cast<int> (depth_mode) );
00393 
00394     XnMapOutputMode current_depth_md =  device_->getDepthOutputMode ();
00395     if (current_depth_md.nXRes != actual_depth_md.nXRes || current_depth_md.nYRes != actual_depth_md.nYRes)
00396       device_->setDepthOutputMode (actual_depth_md);
00397   }
00398   else
00399   {
00400     depth_md = device_->getDefaultDepthMode ();
00401   }
00402 
00403   depth_width_ = depth_md.nXRes;
00404   depth_height_ = depth_md.nYRes;
00405   
00406   if (device_->hasImageStream ())
00407   {
00408     XnMapOutputMode image_md;
00409     if (image_mode != OpenNI_Default_Mode)
00410     {
00411       XnMapOutputMode actual_image_md;
00412       if (!mapConfigMode2XnMode (image_mode, image_md) || !device_->findCompatibleImageMode (image_md, actual_image_md))
00413         PCL_THROW_EXCEPTION (pcl::IOException, "could not find compatible image stream mode " << static_cast<int> (image_mode) );
00414 
00415       XnMapOutputMode current_image_md =  device_->getImageOutputMode ();
00416       if (current_image_md.nXRes != actual_image_md.nXRes || current_image_md.nYRes != actual_image_md.nYRes)
00417         device_->setImageOutputMode (actual_image_md);
00418     }
00419     else
00420     {
00421       image_md = device_->getDefaultImageMode ();
00422     }
00423 
00424     image_width_  = image_md.nXRes;
00425     image_height_ = image_md.nYRes;
00426   }
00427 }
00428 
00430 void
00431 pcl::OpenNIGrabber::startSynchronization ()
00432 {
00433   try
00434   {
00435     if (device_->isSynchronizationSupported () && !device_->isSynchronized () &&
00436         device_->getImageOutputMode ().nFPS == device_->getDepthOutputMode ().nFPS &&
00437         device_->isImageStreamRunning () && device_->isDepthStreamRunning ())
00438         device_->setSynchronization (true);
00439   }
00440   catch (const openni_wrapper::OpenNIException& exception)
00441   {
00442     PCL_THROW_EXCEPTION (pcl::IOException, "Could not start synchronization " << exception.what ());
00443   }
00444 }
00445 
00447 void
00448 pcl::OpenNIGrabber::stopSynchronization ()
00449 {
00450   try
00451   {
00452     if (device_->isSynchronizationSupported () && device_->isSynchronized ())
00453       device_->setSynchronization (false);
00454   }
00455   catch (const openni_wrapper::OpenNIException& exception)
00456   {
00457     PCL_THROW_EXCEPTION (pcl::IOException, "Could not start synchronization " << exception.what ());
00458   }
00459 }
00460 
00462 void
00463 pcl::OpenNIGrabber::imageCallback (boost::shared_ptr<openni_wrapper::Image> image, void*)
00464 {
00465   if (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
00466       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
00467       num_slots<sig_cb_openni_image_depth_image> () > 0)
00468     rgb_sync_.add0 (image, image->getTimeStamp ());
00469 
00470   if (image_signal_->num_slots () > 0)
00471     image_signal_->operator()(image);
00472 }
00473 
00475 void
00476 pcl::OpenNIGrabber::depthCallback (boost::shared_ptr<openni_wrapper::DepthImage> depth_image, void*)
00477 {
00478   if (num_slots<sig_cb_openni_point_cloud_rgb>   () > 0 ||
00479       num_slots<sig_cb_openni_point_cloud_rgba>  () > 0 ||
00480       num_slots<sig_cb_openni_image_depth_image> () > 0)
00481     rgb_sync_.add1 (depth_image, depth_image->getTimeStamp ());
00482 
00483   if (num_slots<sig_cb_openni_point_cloud_i>  () > 0 ||
00484       num_slots<sig_cb_openni_ir_depth_image> () > 0)
00485     ir_sync_.add1 (depth_image, depth_image->getTimeStamp ());
00486 
00487   if (depth_image_signal_->num_slots () > 0)
00488     depth_image_signal_->operator()(depth_image);
00489 
00490   if (point_cloud_signal_->num_slots () > 0)
00491     point_cloud_signal_->operator()(convertToXYZPointCloud(depth_image));
00492 }
00493 
00495 void
00496 pcl::OpenNIGrabber::irCallback (boost::shared_ptr<openni_wrapper::IRImage> ir_image, void*)
00497 {
00498   if (num_slots<sig_cb_openni_point_cloud_i>  () > 0 ||
00499       num_slots<sig_cb_openni_ir_depth_image> () > 0)
00500     ir_sync_.add0(ir_image, ir_image->getTimeStamp ());
00501 
00502   if (ir_image_signal_->num_slots () > 0)
00503     ir_image_signal_->operator()(ir_image);
00504 }
00505 
00507 void
00508 pcl::OpenNIGrabber::imageDepthImageCallback (const boost::shared_ptr<openni_wrapper::Image> &image,
00509                                              const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image)
00510 {
00511   // check if we have color point cloud slots
00512   if (point_cloud_rgb_signal_->num_slots () > 0)
00513   {
00514     PCL_WARN ("PointXYZRGB callbacks deprecated. Use PointXYZRGBA instead.\n");
00515     point_cloud_rgb_signal_->operator()(convertToXYZRGBPointCloud<pcl::PointXYZRGB> (image, depth_image));
00516   }
00517 
00518   if (point_cloud_rgba_signal_->num_slots () > 0)
00519     point_cloud_rgba_signal_->operator()(convertToXYZRGBPointCloud<pcl::PointXYZRGBA> (image, depth_image));
00520 
00521   if (image_depth_image_signal_->num_slots () > 0)
00522   {
00523     float constant = 1.0f / device_->getDepthFocalLength (depth_width_);
00524     image_depth_image_signal_->operator()(image, depth_image, constant);
00525   }
00526 }
00527 
00529 void
00530 pcl::OpenNIGrabber::irDepthImageCallback (const boost::shared_ptr<openni_wrapper::IRImage> &ir_image,
00531                                           const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image)
00532 {
00533   // check if we have color point cloud slots
00534   if (point_cloud_i_signal_->num_slots () > 0)
00535     point_cloud_i_signal_->operator()(convertToXYZIPointCloud (ir_image, depth_image));
00536 
00537   if (ir_depth_image_signal_->num_slots () > 0)
00538   {
00539     float constant = 1.0f / device_->getDepthFocalLength (depth_width_);
00540     ir_depth_image_signal_->operator()(ir_image, depth_image, constant);
00541   }
00542 }
00543 
00545 pcl::PointCloud<pcl::PointXYZ>::Ptr
00546 pcl::OpenNIGrabber::convertToXYZPointCloud (const boost::shared_ptr<openni_wrapper::DepthImage>& depth_image) const
00547 {
00548   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud <pcl::PointXYZ>);
00549 
00550   cloud->height = depth_height_;
00551   cloud->width = depth_width_;
00552   cloud->is_dense = false;
00553 
00554   cloud->points.resize (cloud->height * cloud->width);
00555 
00556   register float constant_x = 1.0f / device_->getDepthFocalLength (depth_width_);
00557   register float constant_y = 1.0f / device_->getDepthFocalLength (depth_width_);
00558   register float centerX = ((float)cloud->width - 1.f) / 2.f;
00559   register float centerY = ((float)cloud->height - 1.f) / 2.f;
00560 
00561   if (pcl_isfinite (depth_focal_length_x_))
00562     constant_x =  1.0f / static_cast<float> (depth_focal_length_x_);
00563 
00564   if (pcl_isfinite (depth_focal_length_y_))
00565     constant_y =  1.0f / static_cast<float> (depth_focal_length_y_);
00566   
00567   if (pcl_isfinite (depth_principal_point_x_))
00568     centerX =  static_cast<float> (depth_principal_point_x_);
00569   
00570   if (pcl_isfinite (depth_principal_point_y_))
00571     centerY =  static_cast<float> (depth_principal_point_y_);
00572 
00573   if (device_->isDepthRegistered ())
00574     cloud->header.frame_id = rgb_frame_id_;
00575   else
00576     cloud->header.frame_id = depth_frame_id_;
00577 
00578 
00579   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00580 
00581   // we have to use Data, since operator[] uses assert -> Debug-mode very slow!
00582   register const unsigned short* depth_map = depth_image->getDepthMetaData ().Data ();
00583   if (depth_image->getWidth() != depth_width_ || depth_image->getHeight () != depth_height_)
00584   {
00585     static unsigned buffer_size = 0;
00586     static boost::shared_array<unsigned short> depth_buffer ((unsigned short*)(NULL));
00587 
00588     if (buffer_size < depth_width_ * depth_height_)
00589     {
00590       buffer_size = depth_width_ * depth_height_;
00591       depth_buffer.reset (new unsigned short [buffer_size]);
00592     }
00593     depth_image->fillDepthImageRaw (depth_width_, depth_height_, depth_buffer.get ());
00594     depth_map = depth_buffer.get ();
00595   }
00596 
00597   register int depth_idx = 0;
00598   for (int v = 0; v < depth_height_; ++v)
00599   {
00600     for (register int u = 0; u < depth_width_; ++u, ++depth_idx)
00601     {
00602       pcl::PointXYZ& pt = cloud->points[depth_idx];
00603       // Check for invalid measurements
00604       if (depth_map[depth_idx] == 0 ||
00605           depth_map[depth_idx] == depth_image->getNoSampleValue () ||
00606           depth_map[depth_idx] == depth_image->getShadowValue ())
00607       {
00608         // not valid
00609         pt.x = pt.y = pt.z = bad_point;
00610         continue;
00611       }
00612       pt.z = depth_map[depth_idx] * 0.001f;
00613       pt.x = (static_cast<float> (u) - centerX) * pt.z * constant_x;
00614       pt.y = (static_cast<float> (v) - centerY) * pt.z * constant_y;
00615     }
00616   }
00617   cloud->sensor_origin_.setZero ();
00618   cloud->sensor_orientation_.w () = 1.0f;
00619   cloud->sensor_orientation_.x () = 0.0f;
00620   cloud->sensor_orientation_.y () = 0.0f;
00621   cloud->sensor_orientation_.z () = 0.0f;  
00622   return (cloud);
00623 }
00624 
00626 template <typename PointT> typename pcl::PointCloud<PointT>::Ptr
00627 pcl::OpenNIGrabber::convertToXYZRGBPointCloud (const boost::shared_ptr<openni_wrapper::Image> &image,
00628                                                const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const
00629 {
00630   static unsigned rgb_array_size = 0;
00631   static boost::shared_array<unsigned char> rgb_array ((unsigned char*)(NULL));
00632   static unsigned char* rgb_buffer = 0;
00633 
00634   boost::shared_ptr<pcl::PointCloud<PointT> > cloud (new pcl::PointCloud<PointT>);
00635 
00636   cloud->header.frame_id = rgb_frame_id_;
00637   cloud->height = std::max (image_height_, depth_height_);
00638   cloud->width = std::max (image_width_, depth_width_);
00639   cloud->is_dense = false;
00640 
00641   cloud->points.resize (cloud->height * cloud->width);
00642 
00643   //float constant = 1.0f / device_->getImageFocalLength (depth_width_);
00644   register float constant_x = 1.0f / device_->getImageFocalLength (depth_width_);
00645   register float constant_y = 1.0f / device_->getImageFocalLength (depth_width_);
00646   register float centerX = ((float)cloud->width - 1.f) / 2.f;
00647   register float centerY = ((float)cloud->height - 1.f) / 2.f;
00648 
00649   if (pcl_isfinite (rgb_focal_length_x_))
00650     constant_x =  1.0f / static_cast<float> (rgb_focal_length_x_);
00651 
00652   if (pcl_isfinite (rgb_focal_length_y_))
00653     constant_y =  1.0f / static_cast<float> (rgb_focal_length_y_);
00654   
00655   if (pcl_isfinite (rgb_principal_point_x_))
00656     centerX =  static_cast<float> (rgb_principal_point_x_);
00657   
00658   if (pcl_isfinite (rgb_principal_point_y_))
00659     centerY =  static_cast<float> (rgb_principal_point_y_);
00660 
00661   register const XnDepthPixel* depth_map = depth_image->getDepthMetaData ().Data ();
00662   if (depth_image->getWidth () != depth_width_ || depth_image->getHeight() != depth_height_)
00663   {
00664     static unsigned buffer_size = 0;
00665     static boost::shared_array<unsigned short> depth_buffer ((unsigned short*)(NULL));
00666 
00667     if (buffer_size < depth_width_ * depth_height_)
00668     {
00669       buffer_size = depth_width_ * depth_height_;
00670       depth_buffer.reset (new unsigned short [buffer_size]);
00671     }
00672 
00673     depth_image->fillDepthImageRaw (depth_width_, depth_height_, depth_buffer.get ());
00674     depth_map = depth_buffer.get ();
00675   }
00676 
00677   // here we need exact the size of the point cloud for a one-one correspondence!
00678   if (rgb_array_size < image_width_ * image_height_ * 3)
00679   {
00680     rgb_array_size = image_width_ * image_height_ * 3;
00681     rgb_array.reset (new unsigned char [rgb_array_size]);
00682     rgb_buffer = rgb_array.get ();
00683   }
00684   image->fillRGB (image_width_, image_height_, rgb_buffer, image_width_ * 3);
00685   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00686 
00687   // set xyz to Nan and rgb to 0 (black)  
00688   if (image_width_ != depth_width_)
00689   {
00690     PointT pt;
00691     pt.x = pt.y = pt.z = bad_point;
00692     pt.b = pt.g = pt.r = 0;
00693     pt.a = 255; // point has no color info -> alpha = max => transparent 
00694     cloud->points.assign (cloud->points.size (), pt);
00695   }
00696   
00697   // fill in XYZ values
00698   unsigned step = cloud->width / depth_width_;
00699   unsigned skip = cloud->width * step - cloud->width;
00700   
00701   int value_idx = 0;
00702   int point_idx = 0;
00703   for (int v = 0; v < depth_height_; ++v, point_idx += skip)
00704   {
00705     for (register int u = 0; u < depth_width_; ++u, ++value_idx, point_idx += step)
00706     {
00707       PointT& pt = cloud->points[point_idx];
00709       // Check for invalid measurements
00710 
00711       if (depth_map[value_idx] != 0 &&
00712           depth_map[value_idx] != depth_image->getNoSampleValue () &&
00713           depth_map[value_idx] != depth_image->getShadowValue ())
00714       {
00715         pt.z = depth_map[value_idx] * 0.001f;
00716         pt.x = (static_cast<float> (u) - centerX) * pt.z * constant_x;
00717         pt.y = (static_cast<float> (v) - centerY) * pt.z * constant_y;
00718       }
00719       else
00720       {
00721         pt.x = pt.y = pt.z = bad_point;
00722       }
00723     }
00724   }
00725 
00726   // fill in the RGB values
00727   step = cloud->width / image_width_;
00728   skip = cloud->width * step - cloud->width;
00729   
00730   value_idx = 0;
00731   point_idx = 0;
00732   RGBValue color;
00733   color.Alpha = 0;
00734 
00735   for (unsigned yIdx = 0; yIdx < image_height_; ++yIdx, point_idx += skip)
00736   {
00737     for (unsigned xIdx = 0; xIdx < image_width_; ++xIdx, point_idx += step, value_idx += 3)
00738     {
00739       PointT& pt = cloud->points[point_idx];
00740       
00741       color.Red   = rgb_buffer[value_idx];
00742       color.Green = rgb_buffer[value_idx + 1];
00743       color.Blue  = rgb_buffer[value_idx + 2];
00744       
00745       pt.rgba = color.long_value;
00746     }
00747   }
00748   cloud->sensor_origin_.setZero ();
00749   cloud->sensor_orientation_.w () = 1.0;
00750   cloud->sensor_orientation_.x () = 0.0;
00751   cloud->sensor_orientation_.y () = 0.0;
00752   cloud->sensor_orientation_.z () = 0.0;
00753   return (cloud);
00754 }
00755 
00757 pcl::PointCloud<pcl::PointXYZI>::Ptr
00758 pcl::OpenNIGrabber::convertToXYZIPointCloud (const boost::shared_ptr<openni_wrapper::IRImage> &ir_image,
00759                                              const boost::shared_ptr<openni_wrapper::DepthImage> &depth_image) const
00760 {
00761   boost::shared_ptr<pcl::PointCloud<pcl::PointXYZI> > cloud (new pcl::PointCloud<pcl::PointXYZI > ());
00762 
00763   cloud->header.frame_id = rgb_frame_id_;
00764   cloud->height = depth_height_;
00765   cloud->width = depth_width_;
00766   cloud->is_dense = false;
00767 
00768   cloud->points.resize (cloud->height * cloud->width);
00769 
00770   //float constant = 1.0f / device_->getImageFocalLength (cloud->width);
00771   register float constant_x = 1.0f / device_->getImageFocalLength (cloud->width);
00772   register float constant_y = 1.0f / device_->getImageFocalLength (cloud->width);
00773   register float centerX = ((float)cloud->width - 1.f) / 2.f;
00774   register float centerY = ((float)cloud->height - 1.f) / 2.f;
00775 
00776   if (pcl_isfinite (rgb_focal_length_x_))
00777     constant_x =  1.0f / static_cast<float> (rgb_focal_length_x_);
00778 
00779   if (pcl_isfinite (rgb_focal_length_y_))
00780     constant_y =  1.0f / static_cast<float> (rgb_focal_length_y_);
00781 
00782   if (pcl_isfinite (rgb_principal_point_x_))
00783     centerX = static_cast<float>(rgb_principal_point_x_);
00784   
00785   if (pcl_isfinite (rgb_principal_point_y_))
00786     centerY = static_cast<float>(rgb_principal_point_y_);
00787 
00788   register const XnDepthPixel* depth_map = depth_image->getDepthMetaData ().Data ();
00789   register const XnIRPixel* ir_map = ir_image->getMetaData ().Data ();
00790 
00791   if (depth_image->getWidth () != depth_width_ || depth_image->getHeight () != depth_height_)
00792   {
00793     static unsigned buffer_size = 0;
00794     static boost::shared_array<unsigned short> depth_buffer ((unsigned short*)(NULL));
00795     static boost::shared_array<unsigned short> ir_buffer ((unsigned short*)(NULL));
00796 
00797     if (buffer_size < depth_width_ * depth_height_)
00798     {
00799       buffer_size = depth_width_ * depth_height_;
00800       depth_buffer.reset (new unsigned short [buffer_size]);
00801       ir_buffer.reset (new unsigned short [buffer_size]);
00802     }
00803 
00804     depth_image->fillDepthImageRaw (depth_width_, depth_height_, depth_buffer.get ());
00805     depth_map = depth_buffer.get ();
00806 
00807     ir_image->fillRaw (depth_width_, depth_height_, ir_buffer.get ());
00808     ir_map = ir_buffer.get ();
00809   }
00810 
00811   register int depth_idx = 0;
00812   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00813 
00814   for (int v = 0; v < depth_height_; ++v)
00815   {
00816     for (register int u = 0; u < depth_width_; ++u, ++depth_idx)
00817     {
00818       pcl::PointXYZI& pt = cloud->points[depth_idx];
00820       // Check for invalid measurements
00821       if (depth_map[depth_idx] == 0 ||
00822           depth_map[depth_idx] == depth_image->getNoSampleValue () ||
00823           depth_map[depth_idx] == depth_image->getShadowValue ())
00824       {
00825         pt.x = pt.y = pt.z = bad_point;
00826       }
00827       else
00828       {
00829         pt.z = depth_map[depth_idx] * 0.001f;
00830         pt.x = (static_cast<float> (u) - centerX) * pt.z * constant_x;
00831         pt.y = (static_cast<float> (v) - centerY) * pt.z * constant_y;
00832       }
00833 
00834       pt.data_c[0] = pt.data_c[1] = pt.data_c[2] = pt.data_c[3] = 0;
00835       pt.intensity = static_cast<float> (ir_map[depth_idx]);
00836     }
00837   }
00838   cloud->sensor_origin_.setZero ();
00839   cloud->sensor_orientation_.w () = 1.0;
00840   cloud->sensor_orientation_.x () = 0.0;
00841   cloud->sensor_orientation_.y () = 0.0;
00842   cloud->sensor_orientation_.z () = 0.0;
00843   return (cloud);
00844 }
00845 
00847 // TODO: delete me?
00848 void
00849 pcl::OpenNIGrabber::updateModeMaps ()
00850 {
00851   XnMapOutputMode output_mode;
00852 
00853   output_mode.nXRes = XN_SXGA_X_RES;
00854   output_mode.nYRes = XN_SXGA_Y_RES;
00855   output_mode.nFPS = 15;
00856   config2xn_map_[OpenNI_SXGA_15Hz] = output_mode;
00857 
00858   output_mode.nXRes = XN_VGA_X_RES;
00859   output_mode.nYRes = XN_VGA_Y_RES;
00860   output_mode.nFPS = 25;
00861   config2xn_map_[OpenNI_VGA_25Hz] = output_mode;
00862   output_mode.nFPS = 30;
00863   config2xn_map_[OpenNI_VGA_30Hz] = output_mode;
00864 
00865   output_mode.nXRes = XN_QVGA_X_RES;
00866   output_mode.nYRes = XN_QVGA_Y_RES;
00867   output_mode.nFPS = 25;
00868   config2xn_map_[OpenNI_QVGA_25Hz] = output_mode;
00869   output_mode.nFPS = 30;
00870   config2xn_map_[OpenNI_QVGA_30Hz] = output_mode;
00871   output_mode.nFPS = 60;
00872   config2xn_map_[OpenNI_QVGA_60Hz] = output_mode;
00873 
00874   output_mode.nXRes = XN_QQVGA_X_RES;
00875   output_mode.nYRes = XN_QQVGA_Y_RES;
00876   output_mode.nFPS = 25;
00877   config2xn_map_[OpenNI_QQVGA_25Hz] = output_mode;
00878   output_mode.nFPS = 30;
00879   config2xn_map_[OpenNI_QQVGA_30Hz] = output_mode;
00880   output_mode.nFPS = 60;
00881   config2xn_map_[OpenNI_QQVGA_60Hz] = output_mode;
00882 }
00883 
00885 bool
00886 pcl::OpenNIGrabber::mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const
00887 {
00888   std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.find (mode);
00889   if (it != config2xn_map_.end ())
00890   {
00891     xnmode = it->second;
00892     return (true);
00893   }
00894   else
00895   {
00896     return (false);
00897   }
00898 }
00899 
00901 std::vector<std::pair<int, XnMapOutputMode> >
00902 pcl::OpenNIGrabber::getAvailableDepthModes () const
00903 {
00904   XnMapOutputMode dummy;
00905   std::vector<std::pair<int, XnMapOutputMode> > result;
00906   for (std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.begin (); it != config2xn_map_.end (); ++it)
00907   {
00908     if (device_->findCompatibleDepthMode (it->second, dummy))
00909       result.push_back (*it);
00910   }
00911 
00912   return (result);
00913 }
00914 
00916 std::vector<std::pair<int, XnMapOutputMode> >
00917 pcl::OpenNIGrabber::getAvailableImageModes () const
00918 {
00919   XnMapOutputMode dummy;
00920   std::vector<std::pair<int, XnMapOutputMode> > result;
00921   for (std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.begin (); it != config2xn_map_.end (); ++it)
00922   {
00923     if (device_->findCompatibleImageMode (it->second, dummy))
00924       result.push_back (*it);
00925   }
00926 
00927   return (result);
00928 }
00929 
00931 float
00932 pcl::OpenNIGrabber::getFramesPerSecond () const
00933 {
00934   return (static_cast<float> (device_->getDepthOutputMode ().nFPS));
00935 }
00936 
00937 #endif


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