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;
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
00077 virtual bool findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00078 virtual bool findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw (OpenNIException);
00079
00080 virtual bool isImageModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00081 virtual bool isDepthModeSupported (const XnMapOutputMode& output_mode) const throw (OpenNIException);
00082
00083 virtual const XnMapOutputMode& getDefaultImageMode () const throw ();
00084 virtual const XnMapOutputMode& getDefaultDepthMode () const throw ();
00085 virtual const XnMapOutputMode& getDefaultIRMode () const throw ();
00086
00087 virtual void setImageOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00088 virtual void setDepthOutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00089 virtual void setIROutputMode (const XnMapOutputMode& output_mode) throw (OpenNIException);
00090
00091 XnMapOutputMode getImageOutputMode () const throw (OpenNIException);
00092 XnMapOutputMode getDepthOutputMode () const throw (OpenNIException);
00093 XnMapOutputMode getIROutputMode () const throw (OpenNIException);
00094
00095 void setDepthRegistration (bool on_off) throw (OpenNIException);
00096 bool isDepthRegistered () const throw (OpenNIException);
00097
00098 virtual void setSynchronization (bool on_off) throw (OpenNIException);
00099 virtual bool isSynchronized () const throw (OpenNIException);
00100 virtual bool isSynchronizationSupported () const throw ();
00101
00102
00103 virtual bool isDepthCropped () const throw (OpenNIException);
00104 virtual void setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException);
00105 virtual bool isDepthCroppingSupported () const throw ();
00106
00110 inline float getImageFocalLength (int output_x_resolution = 0) const throw ();
00111
00115 inline float getDepthFocalLength (int output_x_resolution = 0) const throw ();
00116 inline float getBaseline () const throw ();
00117
00118 virtual void startImageStream () throw (OpenNIException);
00119 virtual void stopImageStream () throw (OpenNIException);
00120
00121 virtual void startDepthStream () throw (OpenNIException);
00122 virtual void stopDepthStream () throw (OpenNIException);
00123
00124 virtual void startIRStream () throw (OpenNIException);
00125 virtual void stopIRStream () throw (OpenNIException);
00126
00127 virtual bool hasImageStream () const throw ();
00128 virtual bool hasDepthStream () const throw ();
00129 virtual bool hasIRStream () const throw ();
00130
00131 bool isImageStreamRunning () const throw (OpenNIException);
00132 bool isDepthStreamRunning () const throw (OpenNIException);
00133 bool isIRStreamRunning () const throw (OpenNIException);
00134
00135 CallbackHandle registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw ();
00136 template<typename T> CallbackHandle registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = NULL) throw ();
00137 bool unregisterImageCallback (const CallbackHandle& callbackHandle) throw ();
00138
00139 CallbackHandle registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw ();
00140 template<typename T> CallbackHandle registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
00141 bool unregisterDepthCallback (const CallbackHandle& callbackHandle) throw ();
00142
00143 CallbackHandle registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = NULL) throw ();
00144 template<typename T> CallbackHandle registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
00145 bool unregisterIRCallback (const CallbackHandle& callbackHandle) throw ();
00146
00150 const char* getSerialNumber () const throw ();
00152 const char* getConnectionString () const throw ();
00153
00154 const char* getVendorName () const throw ();
00155 const char* getProductName () const throw ();
00156 unsigned short getVendorID () const throw ();
00157 unsigned short getProductID () const throw ();
00158 unsigned char getBus () const throw ();
00159 unsigned char getAddress () const throw ();
00160 protected:
00161 typedef boost::function<void(boost::shared_ptr<Image>) > ActualImageCallbackFunction;
00162 typedef boost::function<void(boost::shared_ptr<DepthImage>) > ActualDepthImageCallbackFunction;
00163 typedef boost::function<void(boost::shared_ptr<IRImage>) > ActualIRImageCallbackFunction;
00164
00165 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);
00166 OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException);
00167 static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00168 static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00169 static void __stdcall NewIRDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
00170
00171
00172
00173 void ImageDataThreadFunction () throw (OpenNIException);
00174 void DepthDataThreadFunction () throw (OpenNIException);
00175 void IRDataThreadFunction () throw (OpenNIException);
00176
00177
00178 virtual bool isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0;
00179
00180 void setRegistration (bool on_off) throw (OpenNIException);
00181 virtual boost::shared_ptr<Image> getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () = 0;
00182
00183 virtual void getAvailableModes () throw (OpenNIException);
00184 void Init () throw (OpenNIException);
00185
00186
00187
00188 std::map< CallbackHandle, ActualImageCallbackFunction > image_callback_;
00189 std::map< CallbackHandle, ActualDepthImageCallbackFunction > depth_callback_;
00190 std::map< CallbackHandle, ActualIRImageCallbackFunction > ir_callback_;
00191
00192 std::vector<XnMapOutputMode> available_image_modes_;
00193 std::vector<XnMapOutputMode> available_depth_modes_;
00194
00196 const xn::NodeInfo& device_node_info_;
00198 xn::DepthGenerator depth_generator_;
00200 xn::ImageGenerator image_generator_;
00202 xn::IRGenerator ir_generator_;
00203
00204 XnCallbackHandle depth_callback_handle_;
00205 XnCallbackHandle image_callback_handle_;
00206 XnCallbackHandle ir_callback_handle_;
00207
00209 float depth_focal_length_SXGA_;
00211 float baseline_;
00213 static const float rgb_focal_length_SXGA_;
00214
00215 xn::Context& context_;
00217 XnUInt64 shadow_value_;
00219 XnUInt64 no_sample_value_;
00220
00221 OpenNIDevice::CallbackHandle image_callback_handle_counter_;
00222 OpenNIDevice::CallbackHandle depth_callback_handle_counter_;
00223 OpenNIDevice::CallbackHandle ir_callback_handle_counter_;
00224
00225 bool running_;
00226 mutable boost::mutex image_mutex_;
00227 mutable boost::mutex depth_mutex_;
00228 mutable boost::mutex ir_mutex_;
00229 boost::condition_variable image_condition_;
00230 boost::condition_variable depth_condition_;
00231 boost::condition_variable ir_condition_;
00232 boost::thread image_thread_;
00233 boost::thread depth_thread_;
00234 boost::thread ir_thread_;
00235 };
00236
00237 float OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw ()
00238 {
00239 if (output_x_resolution == 0)
00240 output_x_resolution = getImageOutputMode ().nXRes;
00241
00242 float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00243 return rgb_focal_length_SXGA_ * scale;
00244 }
00245
00246 float OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw ()
00247 {
00248 if (output_x_resolution == 0)
00249 output_x_resolution = getDepthOutputMode ().nXRes;
00250
00251 float scale = output_x_resolution / (float)XN_SXGA_X_RES;
00252 if (isDepthRegistered ())
00253 return rgb_focal_length_SXGA_ * scale;
00254 else
00255 return depth_focal_length_SXGA_ * scale;
00256 }
00257
00258 float OpenNIDevice::getBaseline () const throw ()
00259 {
00260 return baseline_;
00261 }
00262
00263 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* custom_data) throw ()
00264 {
00265 image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data);
00266 return image_callback_handle_counter_++;
00267 }
00268
00269 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* custom_data) throw ()
00270 {
00271 depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data);
00272 return depth_callback_handle_counter_++;
00273 }
00274
00275 template<typename T> OpenNIDevice::CallbackHandle OpenNIDevice::registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* custom_data) throw ()
00276 {
00277 ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data);
00278 return ir_callback_handle_counter_++;
00279 }
00280
00281 }
00282 #endif // __OPENNI_IDEVICE_H__