00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
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;
00065 class OpenNIDevice : public boost::noncopyable
00066 {
00067 public:
00068 typedef boost::function<void(boost::shared_ptr<Image>, void* cookie) > ImageCallbackFunction;
00069 typedef boost::function<void(boost::shared_ptr<DepthImage>, void* cookie) > DepthImageCallbackFunction;
00070 typedef unsigned CallbackHandle;
00071
00072 public:
00073 virtual ~OpenNIDevice () throw ();
00074
00075 virtual bool findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00076 virtual bool findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00077
00078 virtual bool isImageModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00079 virtual bool isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00080
00081 virtual const XnMapOutputMode& getDefaultImageMode () const throw ();
00082 virtual const XnMapOutputMode& getDefaultDepthMode () const throw ();
00083
00084 virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00085 virtual void setDepthOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00086
00087 XnMapOutputMode getImageOutputMode () const throw (OpenNIException);
00088 XnMapOutputMode getDepthOutputMode () const throw (OpenNIException);
00089
00090 void setDepthRegistration (bool on_off) throw (OpenNIException);
00091 bool isDepthRegistered () const throw (OpenNIException);
00092
00093 virtual void setSynchronization (bool on_off) throw (OpenNIException);
00094 virtual bool isSynchronized () const throw (OpenNIException);
00095 virtual bool isSynchronizationSupported () const throw ();
00096
00097
00098 virtual bool isDepthCropped () const throw (OpenNIException);
00099 virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException);
00100 virtual bool isDepthCroppingSupported () const throw ();
00101
00105 inline float getImageFocalLength (int output_x_resolution = 0) const throw ();
00106
00110 inline float getDepthFocalLength (int output_x_resolution = 0) const throw ();
00111 inline float getBaseline () const throw ();
00112
00113 virtual void startImageStream () throw (OpenNIException);
00114 virtual void stopImageStream () throw (OpenNIException);
00115
00116 virtual void startDepthStream () throw (OpenNIException);
00117 virtual void stopDepthStream () throw (OpenNIException);
00118
00119 bool isImageStreamRunning () const throw (OpenNIException);
00120 bool isDepthStreamRunning () const throw (OpenNIException);
00121
00122 CallbackHandle registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw ();
00123 template<typename T> CallbackHandle registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = NULL) throw ();
00124 bool unregisterImageCallback (const CallbackHandle& callbackHandle) throw ();
00125
00126 CallbackHandle registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw ();
00127 template<typename T> CallbackHandle registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
00128 bool unregisterDepthCallback (const CallbackHandle& callbackHandle) throw ();
00129
00133 const char* getSerialNumber () const throw ();
00135 const char* getConnectionString () const throw ();
00136
00137 const char* getVendorName () const throw ();
00138 const char* getProductName () const throw ();
00139 unsigned short getVendorID () const throw ();
00140 unsigned short getProductID () const throw ();
00141 unsigned char getBus () const throw ();
00142 unsigned char getAddress () const throw ();
00143 protected:
00144 typedef boost::function<void(boost::shared_ptr<Image>) > ActualImageCallbackFunction;
00145 typedef boost::function<void(boost::shared_ptr<DepthImage>) > ActualDepthImageCallbackFunction;
00146
00147 OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node) throw (OpenNIException);
00148 static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00149 static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00150
00151
00152
00153 void ImageDataThreadFunction () throw (OpenNIException);
00154 void DepthDataThreadFunction () throw (OpenNIException);
00155
00156
00157 virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0;
00158
00159 void setRegistration (bool on_off) throw (OpenNIException);
00160 virtual boost::shared_ptr<Image> getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () = 0;
00161
00162 virtual void getAvailableModes () throw (OpenNIException);
00163 void Init () throw (OpenNIException);
00164
00165
00166
00167 std::map< CallbackHandle, ActualImageCallbackFunction > image_callback_;
00168 std::map< CallbackHandle, ActualDepthImageCallbackFunction > depth_callback_;
00169
00170 std::vector<XnMapOutputMode> available_image_modes_;
00171 std::vector<XnMapOutputMode> available_depth_modes_;
00172
00174 const xn::NodeInfo& device_node_info_;
00176 xn::DepthGenerator depth_generator_;
00178 xn::ImageGenerator image_generator_;
00179
00180 XnCallbackHandle depth_callback_handle_;
00181 XnCallbackHandle image_callback_handle_;
00182
00184 float depth_focal_length_SXGA_;
00186 float baseline_;
00188 static const float rgb_focal_length_SXGA_;
00189
00190 xn::Context& context_;
00192 XnUInt64 shadow_value_;
00194 XnUInt64 no_sample_value_;
00195
00196 OpenNIDevice::CallbackHandle image_callback_handle_counter_;
00197 OpenNIDevice::CallbackHandle depth_callback_handle_counter_;
00198
00199 bool running_;
00200 mutable boost::mutex image_mutex_;
00201 mutable boost::mutex depth_mutex_;
00202 boost::condition_variable image_condition_;
00203 boost::condition_variable depth_condition_;
00204 boost::thread image_thread_;
00205 boost::thread depth_thread_;
00206 };
00207
00208 float OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw ()
00209 {
00210 if (output_x_resolution == 0)
00211 output_x_resolution = getImageOutputMode ().nXRes;
00212
00213 float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00214 return rgb_focal_length_SXGA_ * scale;
00215 }
00216
00217 float OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw ()
00218 {
00219 if (output_x_resolution == 0)
00220 output_x_resolution = getDepthOutputMode ().nXRes;
00221
00222 float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00223 if (isDepthRegistered ())
00224 return rgb_focal_length_SXGA_ * scale;
00225 else
00226 return depth_focal_length_SXGA_ * scale;
00227 }
00228
00229 float OpenNIDevice::getBaseline () const throw ()
00230 {
00231 return baseline_;
00232 }
00233
00234 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* custom_data) throw ()
00235 {
00236 image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data);
00237 return image_callback_handle_counter_++;
00238 }
00239
00240 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* custom_data) throw ()
00241 {
00242 depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data);
00243 return depth_callback_handle_counter_++;
00244 }
00245 }
00246 #endif // __OPENNI_IDEVICE_H__