openni_device_primesense.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011 2011 Willow Garage, Inc.
00005  *    Suat Gedikli <gedikli@willowgarage.com>
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 Willow Garage, Inc. 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 #include <pcl/pcl_config.h>
00038 #ifdef HAVE_OPENNI
00039 
00040 #include <pcl/io/openni_camera/openni_device_primesense.h>
00041 #include <pcl/io/openni_camera/openni_image_yuv_422.h>
00042 #include <iostream>
00043 #include <sstream>
00044 #include <boost/thread/mutex.hpp>
00045 
00046 using namespace std;
00047 using namespace boost;
00048 
00049 namespace openni_wrapper
00050 {
00051 
00052 DevicePrimesense::DevicePrimesense (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node)
00053 : OpenNIDevice (context, device_node, image_node, depth_node, ir_node)
00054 {
00055   // setup stream modes
00056   enumAvailableModes ();
00057   setDepthOutputMode (getDefaultDepthMode ());
00058   setImageOutputMode (getDefaultImageMode ());
00059   setIROutputMode (getDefaultIRMode ());
00060 
00061   unique_lock<mutex> image_lock(image_mutex_);
00062   XnStatus status = image_generator_.SetIntProperty ("InputFormat", 5);
00063   if (status != XN_STATUS_OK)
00064     THROW_OPENNI_EXCEPTION ("Error setting the image input format to Uncompressed YUV422. Reason: %s", xnGetStatusString (status));
00065 
00066   status = image_generator_.SetPixelFormat (XN_PIXEL_FORMAT_YUV422);
00067   if (status != XN_STATUS_OK)
00068     THROW_OPENNI_EXCEPTION ("Failed to set image pixel format to YUV422. Reason: %s", xnGetStatusString (status));
00069 
00070   image_lock.unlock ();
00071 
00072   lock_guard<mutex> depth_lock(depth_mutex_);
00073   status = depth_generator_.SetIntProperty ("RegistrationType", 1);
00074   if (status != XN_STATUS_OK)
00075     THROW_OPENNI_EXCEPTION ("Error setting the registration type. Reason: %s", xnGetStatusString (status));
00076 }
00077 
00078 DevicePrimesense::~DevicePrimesense () throw ()
00079 {
00080   setDepthRegistration ( false );
00081   setSynchronization ( false );
00082 
00083   depth_mutex_.lock ();
00084   depth_generator_.UnregisterFromNewDataAvailable (depth_callback_handle_);
00085   depth_mutex_.unlock ();
00086 
00087   image_mutex_.lock ();
00088   image_generator_.UnregisterFromNewDataAvailable (image_callback_handle_);
00089   image_mutex_.unlock ();
00090 }
00091 
00092 bool DevicePrimesense::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw ()
00093 {
00094   return ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height);
00095 }
00096 
00097 //void DevicePrimesense::setImageOutputMode (const XnMapOutputMode& output_mode)
00098 //{
00099 //  if (output_mode.nFPS == 30 && output_mode.nXRes == XN_UXGA_X_RES && output_mode.nYRes == XN_UXGA_Y_RES )
00100 //  {
00101 //    cout << "setting image mode to UXGA" << endl;
00102 //    if (isImageStreamRunning ())
00103 //    {
00104 //      stopImageStream ();
00105 //      XnStatus status = image_generator_.SetIntProperty ("InputFormat", 0);
00106 //      if (status != XN_STATUS_OK)
00107 //        THROW_OPENNI_EXCEPTION ("Error setting the image input format to compressed BAYER. Reason: %s", xnGetStatusString (status));
00108 //      status = image_generator_.SetPixelFormat (XN_PIXEL_FORMAT_RGB24);
00109 //      if (status != XN_STATUS_OK)
00110 //        THROW_OPENNI_EXCEPTION ("Failed to set image pixel format to YUV422. Reason: %s", xnGetStatusString (status));
00111 //      sleep (1);
00112 //      startImageStream ();
00113 //    }
00114 //    else
00115 //    {
00116 //      XnStatus status = image_generator_.SetIntProperty ("InputFormat", 0);
00117 //      if (status != XN_STATUS_OK)
00118 //        THROW_OPENNI_EXCEPTION ("Error setting the image input format to compressed BAYER. Reason: %s", xnGetStatusString (status));
00119 //
00120 //      status = image_generator_.SetPixelFormat (XN_PIXEL_FORMAT_GRAYSCALE_8_BIT);
00121 //      if (status != XN_STATUS_OK)
00122 //        THROW_OPENNI_EXCEPTION ("Failed to set image pixel format to YUV422. Reason: %s", xnGetStatusString (status));
00123 //    }
00124 //  }
00125 //  else
00126 //  {
00127 //    XnStatus status = image_generator_.SetIntProperty ("InputFormat", 5);
00128 //    if (status != XN_STATUS_OK)
00129 //        THROW_OPENNI_EXCEPTION ("Error setting the image input format to uncompressed BAYER. Reason: %s", xnGetStatusString (status));
00130 //
00131 //    status = image_generator_.SetPixelFormat (XN_PIXEL_FORMAT_YUV422);
00132 //    if (status != XN_STATUS_OK)
00133 //      THROW_OPENNI_EXCEPTION ("Failed to set image pixel format to YUV422. Reason: %s", xnGetStatusString (status));
00134 //  }
00135 //  OpenNIDevice::setImageOutputMode (output_mode);
00136 //}
00137 
00138 void DevicePrimesense::enumAvailableModes () throw ()
00139 {
00140   XnMapOutputMode output_mode;
00141   available_image_modes_.clear();
00142   available_depth_modes_.clear();
00143 
00144   // Depth Modes
00145   output_mode.nFPS = 30;
00146   output_mode.nXRes = XN_VGA_X_RES;
00147   output_mode.nYRes = XN_VGA_Y_RES;
00148   available_depth_modes_.push_back (output_mode);
00149 
00150   output_mode.nFPS = 25;
00151   output_mode.nXRes = XN_VGA_X_RES;
00152   output_mode.nYRes = XN_VGA_Y_RES;
00153   available_depth_modes_.push_back (output_mode);
00154 
00155   output_mode.nFPS = 25;
00156   output_mode.nXRes = XN_QVGA_X_RES;
00157   output_mode.nYRes = XN_QVGA_Y_RES;
00158   available_depth_modes_.push_back (output_mode);
00159 
00160   output_mode.nFPS = 30;
00161   output_mode.nXRes = XN_QVGA_X_RES;
00162   output_mode.nYRes = XN_QVGA_Y_RES;
00163   available_depth_modes_.push_back (output_mode);
00164 
00165   output_mode.nFPS = 60;
00166   output_mode.nXRes = XN_QVGA_X_RES;
00167   output_mode.nYRes = XN_QVGA_Y_RES;
00168   available_depth_modes_.push_back (output_mode);
00169 
00170   // RGB Modes
00171   output_mode.nFPS = 30;
00172   output_mode.nXRes = XN_VGA_X_RES;
00173   output_mode.nYRes = XN_VGA_Y_RES;
00174   available_image_modes_.push_back (output_mode);
00175 
00176   output_mode.nFPS = 25;
00177   output_mode.nXRes = XN_VGA_X_RES;
00178   output_mode.nYRes = XN_VGA_Y_RES;
00179   available_image_modes_.push_back (output_mode);
00180 
00181 //  output_mode.nFPS = 30;
00182 //  output_mode.nXRes = XN_UXGA_X_RES;
00183 //  output_mode.nYRes = XN_UXGA_Y_RES;
00184 //  available_image_modes_.push_back (output_mode);
00185 
00186   output_mode.nFPS = 25;
00187   output_mode.nXRes = XN_QVGA_X_RES;
00188   output_mode.nYRes = XN_QVGA_Y_RES;
00189   available_image_modes_.push_back (output_mode);
00190 
00191   output_mode.nFPS = 30;
00192   output_mode.nXRes = XN_QVGA_X_RES;
00193   output_mode.nYRes = XN_QVGA_Y_RES;
00194   available_image_modes_.push_back (output_mode);
00195 
00196   output_mode.nFPS = 60;
00197   output_mode.nXRes = XN_QVGA_X_RES;
00198   output_mode.nYRes = XN_QVGA_Y_RES;
00199   available_image_modes_.push_back (output_mode);
00200 }
00201 
00202 boost::shared_ptr<Image> DevicePrimesense::getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw ()
00203 {
00204   return boost::shared_ptr<Image> ( new ImageYUV422 (image_data) );
00205 }
00206 
00207 void DevicePrimesense::startImageStream ()
00208 {
00209   // Suat: Ugly workaround... but on some usb-ports its not possible to start the image stream after the depth stream.
00210   // turning on and off registration solves for some reason the problem!
00211 
00212   if (isDepthStreamRunning ())
00213   {
00214     if (isDepthRegistered ())
00215     {
00216      // Reset the view point
00217       setDepthRegistration (false);
00218 
00219       // Reset the view point
00220       setDepthRegistration (true);
00221 
00222      // Reset the view point
00223       setDepthRegistration (false);
00224 
00225       // Start the stream
00226       OpenNIDevice::startImageStream ();
00227 
00228       // Register the stream
00229       setDepthRegistration (true);
00230     }
00231     else
00232     {
00233       // Reset the view point
00234       setDepthRegistration (true);
00235       // Reset the view point
00236       setDepthRegistration (false);
00237 
00238       // Start the stream
00239       OpenNIDevice::startImageStream ();
00240     }
00241   }
00242   else
00243     // Start the stream
00244     OpenNIDevice::startImageStream ();
00245 }
00246 
00247 void DevicePrimesense::startDepthStream ()
00248 {
00249   if (isDepthRegistered ())
00250   {
00251     // Reset the view point
00252     setDepthRegistration (false);
00253 
00254     // Start the stream
00255     OpenNIDevice::startDepthStream ();
00256 
00257     // Register the stream
00258     setDepthRegistration (true);
00259   }
00260   else
00261     // Start the stream
00262     OpenNIDevice::startDepthStream ();
00263 }
00264 
00265 }//namespace
00266 #endif


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