openni_device.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 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 
00038 #ifndef __OPENNI_IDEVICE_H__
00039 #define __OPENNI_IDEVICE_H__
00040 #include <map>
00041 #include <vector>
00042 #include <utility>
00043 #include "openni_exception.h"
00044 #include <XnCppWrapper.h>
00045 #include <boost/noncopyable.hpp>
00046 #include <boost/function.hpp>
00047 #include <boost/thread.hpp>
00048 #include <boost/thread/condition.hpp>
00049 
00051 
00052 #ifndef _WIN32
00053 #define __stdcall
00054 #endif
00055 
00056 namespace openni_wrapper
00057 {
00058 class Image;
00059 class DepthImage;
00060 class IRImage;
00066 class OpenNIDevice : public boost::noncopyable
00067 {
00068 public:
00069   typedef boost::function<void(boost::shared_ptr<Image>, void* cookie) > ImageCallbackFunction;
00070   typedef boost::function<void(boost::shared_ptr<DepthImage>, void* cookie) > DepthImageCallbackFunction;
00071   typedef boost::function<void(boost::shared_ptr<IRImage>, void* cookie) > IRImageCallbackFunction;
00072   typedef unsigned CallbackHandle;
00073 
00074 public:
00075   virtual ~OpenNIDevice () throw ();
00076   void shutdown ();
00077 
00078   virtual bool findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00079   virtual bool findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00080 
00081   virtual bool isImageModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00082   virtual bool isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00083 
00084   virtual const XnMapOutputMode& getDefaultImageMode () const throw ();
00085   virtual const XnMapOutputMode& getDefaultDepthMode () const throw ();
00086   virtual const XnMapOutputMode& getDefaultIRMode () const throw ();
00087 
00088   virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00089   virtual void setDepthOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00090   virtual void setIROutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00091 
00092   XnMapOutputMode getImageOutputMode () const throw (OpenNIException);
00093   XnMapOutputMode getDepthOutputMode () const throw (OpenNIException);
00094   XnMapOutputMode getIROutputMode () const throw (OpenNIException);
00095 
00096   virtual void setDepthRegistration (bool on_off) throw (OpenNIException);
00097   bool isDepthRegistered () const throw (OpenNIException);
00098   virtual bool isDepthRegistrationSupported () const throw (OpenNIException);
00099   
00100   virtual void setSynchronization (bool on_off) throw (OpenNIException);
00101   virtual bool isSynchronized () const throw (OpenNIException);
00102   virtual bool isSynchronizationSupported () const throw ();
00103 
00104   // just supported by primesense -> virtual
00105   virtual bool isDepthCropped () const throw (OpenNIException);
00106   virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException);
00107   virtual bool isDepthCroppingSupported () const throw ();
00108 
00112   inline float getImageFocalLength (int output_x_resolution = 0) const throw ();
00113 
00117   inline float getDepthFocalLength (int output_x_resolution = 0) const throw ();
00118   inline float getBaseline () const throw ();
00119 
00120   virtual void startImageStream () throw (OpenNIException);
00121   virtual void stopImageStream () throw (OpenNIException);
00122 
00123   virtual void startDepthStream () throw (OpenNIException);
00124   virtual void stopDepthStream () throw (OpenNIException);
00125 
00126   virtual void startIRStream () throw (OpenNIException);
00127   virtual void stopIRStream () throw (OpenNIException);
00128 
00129   bool hasImageStream () const throw ();
00130   bool hasDepthStream () const throw ();
00131   bool hasIRStream () const throw ();
00132 
00133   virtual bool isImageStreamRunning () const throw (OpenNIException);
00134   virtual bool isDepthStreamRunning () const throw (OpenNIException);
00135   virtual bool isIRStreamRunning () const throw (OpenNIException);
00136 
00137   CallbackHandle registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw ();
00138   template<typename T> CallbackHandle registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = NULL) throw ();
00139   bool unregisterImageCallback (const CallbackHandle& callbackHandle) throw ();
00140 
00141   CallbackHandle registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw ();
00142   template<typename T> CallbackHandle registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
00143   bool unregisterDepthCallback (const CallbackHandle& callbackHandle) throw ();
00144 
00145   CallbackHandle registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = NULL) throw ();
00146   template<typename T> CallbackHandle registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
00147   bool unregisterIRCallback (const CallbackHandle& callbackHandle) throw ();
00148 
00152   const char* getSerialNumber () throw ();
00154   const char* getConnectionString () const throw ();
00155 
00156   const char* getVendorName () const throw ();
00157   const char* getProductName () const throw ();
00158   unsigned short getVendorID () const throw ();
00159   unsigned short getProductID () const throw ();
00160   unsigned char  getBus () const throw ();
00161   unsigned char  getAddress () const throw ();
00162 protected:
00163   typedef boost::function<void(boost::shared_ptr<Image>) > ActualImageCallbackFunction;
00164   typedef boost::function<void(boost::shared_ptr<DepthImage>) > ActualDepthImageCallbackFunction;
00165   typedef boost::function<void(boost::shared_ptr<IRImage>) > ActualIRImageCallbackFunction;
00166 
00167   OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException);
00168   OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException);
00169   OpenNIDevice (xn::Context& context) throw (OpenNIException);
00170   static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00171   static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00172   static void __stdcall NewIRDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00173 
00174   // This is a workaround, since in the NewDepthDataAvailable function WaitAndUpdateData leads to a dead-lock behaviour
00175   // and retrieving image data without WaitAndUpdateData leads to incomplete images!!!
00176   void ImageDataThreadFunction () throw (OpenNIException);
00177   void DepthDataThreadFunction () throw (OpenNIException);
00178   void IRDataThreadFunction () throw (OpenNIException);
00179 
00180   virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const  throw () = 0;
00181 
00182   void setRegistration (bool on_off) throw (OpenNIException);
00183   virtual boost::shared_ptr<Image> getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () = 0;
00184 
00185   virtual void enumAvailableModes () throw (OpenNIException);
00186   void Init () throw (OpenNIException); 
00187   // holds the callback functions together with custom data
00188   // since same callback function can be registered multiple times with e.g. different custom data
00189   // we use a map structure with a handle as the key
00190   std::map< CallbackHandle, ActualImageCallbackFunction > image_callback_;
00191   std::map< CallbackHandle, ActualDepthImageCallbackFunction > depth_callback_;
00192   std::map< CallbackHandle, ActualIRImageCallbackFunction > ir_callback_;
00193 
00194   std::vector<XnMapOutputMode> available_image_modes_;
00195   std::vector<XnMapOutputMode> available_depth_modes_;
00196 
00198   xn::Context& context_;
00200   xn::NodeInfo device_node_info_;
00201   
00203   xn::DepthGenerator depth_generator_;
00205   xn::ImageGenerator image_generator_;
00207   xn::IRGenerator ir_generator_;
00208 
00209   XnCallbackHandle depth_callback_handle_;
00210   XnCallbackHandle image_callback_handle_;
00211   XnCallbackHandle ir_callback_handle_;
00212 
00214   float depth_focal_length_SXGA_;
00216   float baseline_;
00218   static const float rgb_focal_length_SXGA_;
00219 
00221   XnUInt64 shadow_value_;
00223   XnUInt64 no_sample_value_;
00224 
00225   OpenNIDevice::CallbackHandle image_callback_handle_counter_;
00226   OpenNIDevice::CallbackHandle depth_callback_handle_counter_;
00227   OpenNIDevice::CallbackHandle ir_callback_handle_counter_;
00228 
00229   bool quit_;
00230   mutable boost::mutex image_mutex_;
00231   mutable boost::mutex depth_mutex_;
00232   mutable boost::mutex ir_mutex_;
00233   boost::condition_variable image_condition_;
00234   boost::condition_variable depth_condition_;
00235   boost::condition_variable ir_condition_;
00236   boost::thread_group data_threads_;
00237 };
00238 
00239 float OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw ()
00240 {
00241   if (output_x_resolution == 0)
00242     output_x_resolution = getImageOutputMode ().nXRes;
00243 
00244   float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00245   return rgb_focal_length_SXGA_ * scale;
00246 }
00247 
00248 float OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw ()
00249 {
00250   if (output_x_resolution == 0)
00251     output_x_resolution = getDepthOutputMode ().nXRes;
00252 
00253   float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00254   if (isDepthRegistered ())
00255     return rgb_focal_length_SXGA_ * scale;
00256   else
00257     return depth_focal_length_SXGA_ * scale;
00258 }
00259 
00260 float OpenNIDevice::getBaseline () const throw ()
00261 {
00262   return baseline_;
00263 }
00264 
00265 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* custom_data) throw ()
00266 {
00267   image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data);
00268   return image_callback_handle_counter_++;
00269 }
00270 
00271 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* custom_data) throw ()
00272 {
00273   depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback,  boost::ref (instance), _1, custom_data);
00274   return depth_callback_handle_counter_++;
00275 }
00276 
00277 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* custom_data) throw ()
00278 {
00279   ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback,  boost::ref (instance), _1, custom_data);
00280   return ir_callback_handle_counter_++;
00281 }
00282 
00283 }
00284 #endif // __OPENNI_IDEVICE_H__


openni_camera
Author(s): Patrick Mihelich, Suat Gedikli, Radu Bogdan Rusu
autogenerated on Mon Oct 6 2014 03:06:43