Point Cloud Library (PCL)  1.8.1
openni_device.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2009-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #include <pcl/pcl_config.h>
39 #ifdef HAVE_OPENNI
40 
41 #ifndef __OPENNI_IDEVICE_H__
42 #define __OPENNI_IDEVICE_H__
43 #include <map>
44 #include <vector>
45 #include <utility>
46 #include "openni_exception.h"
47 #include "openni.h"
48 
49 #include <pcl/io/boost.h>
50 #include <pcl/pcl_macros.h>
51 
52 
53 /// @todo Get rid of all exception-specifications, these are useless and soon to be deprecated
54 
55 #ifndef _WIN32
56 #define __stdcall
57 #endif
58 
59 namespace openni_wrapper
60 {
61  class Image;
62  class DepthImage;
63  class IRImage;
64 
65  /** \brief Class representing an astract device for OpenNI devices: Primesense PSDK, Microsoft Kinect, Asus Xtion Pro/Live.
66  * \author Suat Gedikli
67  * \ingroup io
68  */
69  class PCL_EXPORTS OpenNIDevice
70  {
71  public:
72  typedef enum
73  {
74  OpenNI_shift_values = 0, // Shift values (disparity)
75  OpenNI_12_bit_depth = 1, // Default mode: regular 12-bit depth
76  } DepthMode;
77 
78  typedef boost::function<void(boost::shared_ptr<Image>, void* cookie) > ImageCallbackFunction;
79  typedef boost::function<void(boost::shared_ptr<DepthImage>, void* cookie) > DepthImageCallbackFunction;
80  typedef boost::function<void(boost::shared_ptr<IRImage>, void* cookie) > IRImageCallbackFunction;
81  typedef unsigned CallbackHandle;
82 
83  public:
84 
85  /** \brief virtual destructor. Never throws an exception. */
86  virtual ~OpenNIDevice () throw ();
87 
88  /** \brief finds an image output mode that can be used to retrieve images in desired output mode.
89  * e.g If device just supports VGA at 30Hz, then the desired mode QVGA at 30Hz would be possible by down sampling,
90  * but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible.
91  * \param[in] output_mode the desired output mode
92  * \param[out] mode the compatible mode that the device natively supports.
93  * \return true, if a compatible mode could be found, false otherwise.
94  */
95  bool
96  findCompatibleImageMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw ();
97 
98  /** \brief finds a depth output mode that can be used to retrieve depth images in desired output mode.
99  * e.g If device just supports VGA at 30Hz, then a desired mode of QVGA at 30Hz would be possbile by downsampling,
100  * but the modes VGA at 25Hz and SXGA at 30Hz would not be compatible.
101  * \param[in] output_mode the desired output mode
102  * \param[out] mode the compatible mode that the device natively supports.
103  * \return true, if a compatible mode could be found, false otherwise.
104  */
105  bool
106  findCompatibleDepthMode (const XnMapOutputMode& output_mode, XnMapOutputMode& mode ) const throw ();
107 
108  /** \brief returns whether a given mode is natively supported by the device or not
109  * \param[in] output_mode mode to be checked
110  * \return true if mode natively available, false otherwise
111  */
112  bool
113  isImageModeSupported (const XnMapOutputMode& output_mode) const throw ();
114 
115  /** \brief returns whether a given mode is natively supported by the device or not
116  * \param[in] output_mode mode to be checked
117  * \return true if mode natively available, false otherwise
118  */
119  bool
120  isDepthModeSupported (const XnMapOutputMode& output_mode) const throw ();
121 
122  /** \brief returns the default image mode, which is simply the first entry in the list of modes
123  * \return the default image mode
124  */
125  const XnMapOutputMode&
126  getDefaultImageMode () const throw ();
127 
128  /** \brief returns the default depth mode, which is simply the first entry in the list of modes
129  * \return the default depth mode
130  */
131  const XnMapOutputMode&
132  getDefaultDepthMode () const throw ();
133 
134  /** \brief returns the default IR mode, which is simply the first entry in the list of modes
135  * \return the default IR mode
136  */
137  const XnMapOutputMode&
138  getDefaultIRMode () const throw ();
139 
140  /** \brief sets the output mode of the image stream
141  * \param[in] output_mode the desired output mode
142  */
143  void
144  setImageOutputMode (const XnMapOutputMode& output_mode);
145 
146  /** \brief sets the output mode of the depth stream
147  * \param[in] output_mode the desired output mode
148  */
149  void
150  setDepthOutputMode (const XnMapOutputMode& output_mode);
151 
152  /** \brief sets the output mode of the IR stream
153  * \param[in] output_mode the desired output mode
154  */
155  void
156  setIROutputMode (const XnMapOutputMode& output_mode);
157 
158  /** \return the current output mode of the image stream */
159  XnMapOutputMode
160  getImageOutputMode () const;
161 
162  /** \return the current output mode of the depth stream */
163  XnMapOutputMode
164  getDepthOutputMode () const;
165 
166  /** \return the current output mode of the IR stream */
167  XnMapOutputMode
168  getIROutputMode () const;
169 
170  /** \brief set the depth stream registration on or off
171  * \param[in] on_off
172  */
173  void
174  setDepthRegistration (bool on_off);
175 
176  /** \return whether the depth stream is registered to the RGB camera fram or not. */
177  bool
178  isDepthRegistered () const throw ();
179 
180  /** \return whether a registration of the depth stream to the RGB camera frame is supported or not. */
181  bool
182  isDepthRegistrationSupported () const throw ();
183 
184  /** \brief set the hardware synchronization between Depth and RGB stream on or off.
185  * \param[in] on_off
186  */
187  void
188  setSynchronization (bool on_off);
189 
190  /** \return true if Depth stream is synchronized to RGB stream, false otherwise. */
191  bool
192  isSynchronized () const throw ();
193 
194  /** \return true if the Device supports hardware synchronization between Depth and RGB streams or not. */
195  virtual bool
196  isSynchronizationSupported () const throw ();
197 
198  /** \return true if depth stream is a cropped version of the native depth stream, false otherwise. */
199  bool
200  isDepthCropped () const;
201 
202  /** \brief turn on cropping for the depth stream.
203  * \param[in] x x-position of the rectangular subregion.
204  * \param[in] y y-position of the rectangular subregion.
205  * \param[in] width width of the rectangular subregion.
206  * \param[in] height height of the rectangular subregion.
207  */
208  void
209  setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height);
210 
211  /** \return true if cropping of the depth stream is supported, false otherwise. */
212  bool
213  isDepthCroppingSupported () const throw ();
214 
215  /** \brief returns the focal length for the color camera in pixels. The pixels are assumed to be square.
216  * Result depends on the output resolution of the image.
217  */
218  inline float
219  getImageFocalLength (int output_x_resolution = 0) const throw ();
220 
221  /** \brief returns the focal length for the IR camera in pixels. The pixels are assumed to be square.
222  * Result depends on the output resolution of the depth image.
223  */
224  inline float
225  getDepthFocalLength (int output_x_resolution = 0) const throw ();
226 
227  /** \return Baseline of the "stereo" frame. i.e. for PSDK compatible devices its the distance between the Projector and the IR camera. */
228  inline float
229  getBaseline () const throw ();
230 
231  /** \brief starts the image stream. */
232  virtual void
233  startImageStream ();
234 
235  /** \brief stops the image stream. */
236  virtual void
237  stopImageStream ();
238 
239  /** \brief starts the depth stream. */
240  virtual void
241  startDepthStream ();
242 
243  /** \brief stops the depth stream. */
244  virtual void
245  stopDepthStream ();
246 
247  /** \brief starts the IR stream. */
248  virtual void
249  startIRStream ();
250 
251  /** \brief stops the IR stream. */
252  virtual void
253  stopIRStream ();
254 
255  /** \return true if the device supports an image stream, false otherwise. */
256  bool
257  hasImageStream () const throw ();
258 
259  /** \return true if the device supports a depth stream, false otherwise. */
260  bool
261  hasDepthStream () const throw ();
262 
263  /** \return true if the device supports an IR stream, false otherwise. */
264  bool
265  hasIRStream () const throw ();
266 
267  /** \return true if the image stream is running / started, false otherwise. */
268  virtual bool
269  isImageStreamRunning () const throw ();
270 
271  /** \return true if the depth stream is running / started, false otherwise. */
272  virtual bool
273  isDepthStreamRunning () const throw ();
274 
275  /** \return true if the IR stream is running / started, false otherwise. */
276  virtual bool
277  isIRStreamRunning () const throw ();
278 
279  /** \brief registers a callback function of boost::function type for the image stream with an optional user defined parameter.
280  * The callback will always be called with a new image and the user data "cookie".
281  * \param[in] callback the user callback to be called if a new image is available
282  * \param[in] cookie the cookie that needs to be passed to the callback together with the new image.
283  * \return a callback handler that can be used to remove the user callback from list of image-stream callbacks.
284  */
285  CallbackHandle
286  registerImageCallback (const ImageCallbackFunction& callback, void* cookie = NULL) throw ();
287 
288  /** \brief registers a callback function for the image stream with an optional user defined parameter.
289  * This version is used to register a member function of any class.
290  * The callback will always be called with a new image and the user data "cookie".
291  * \param[in] callback the user callback to be called if a new image is available
292  * \param instance
293  * \param[in] cookie the cookie that needs to be passed to the callback together with the new image.
294  * \return a callback handler that can be used to remove the user callback from list of image-stream callbacks.
295  */
296  template<typename T> CallbackHandle
297  registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* cookie = NULL) throw ();
298 
299  /** \brief unregisters a callback function. i.e. removes that function from the list of image stream callbacks.
300  * \param[in] callbackHandle the handle of the callback to unregister.
301  * \return true, if callback was in list and could be unregistered, false otherwise.
302  */
303  bool
304  unregisterImageCallback (const CallbackHandle& callbackHandle) throw ();
305 
306 
307  /** \brief registers a callback function of boost::function type for the depth stream with an optional user defined parameter.
308  * The callback will always be called with a new depth image and the user data "cookie".
309  * \param[in] callback the user callback to be called if a new depth image is available
310  * \param[in] cookie the cookie that needs to be passed to the callback together with the new depth image.
311  * \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks.
312  */
313  CallbackHandle
314  registerDepthCallback (const DepthImageCallbackFunction& callback, void* cookie = NULL) throw ();
315 
316  /** \brief registers a callback function for the depth stream with an optional user defined parameter.
317  * This version is used to register a member function of any class.
318  * The callback will always be called with a new depth image and the user data "cookie".
319  * \param[in] callback the user callback to be called if a new depth image is available
320  * \param instance
321  * \param[in] cookie the cookie that needs to be passed to the callback together with the new depth image.
322  * \return a callback handler that can be used to remove the user callback from list of depth-stream callbacks.
323  */
324  template<typename T> CallbackHandle
325  registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
326 
327  /** \brief unregisters a callback function. i.e. removes that function from the list of depth stream callbacks.
328  * \param[in] callbackHandle the handle of the callback to unregister.
329  * \return true, if callback was in list and could be unregistered, false otherwise.
330  */
331  bool
332  unregisterDepthCallback (const CallbackHandle& callbackHandle) throw ();
333 
334  /** \brief registers a callback function of boost::function type for the IR stream with an optional user defined parameter.
335  * The callback will always be called with a new IR image and the user data "cookie".
336  * \param[in] callback the user callback to be called if a new IR image is available
337  * \param[in] cookie the cookie that needs to be passed to the callback together with the new IR image.
338  * \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks.
339  */
340  CallbackHandle
341  registerIRCallback (const IRImageCallbackFunction& callback, void* cookie = NULL) throw ();
342 
343  /** \brief registers a callback function for the IR stream with an optional user defined parameter.
344  * This version is used to register a member function of any class.
345  * The callback will always be called with a new IR image and the user data "cookie".
346  * \param[in] callback the user callback to be called if a new IR image is available
347  * \param instance
348  * \param[in] cookie the cookie that needs to be passed to the callback together with the new IR image.
349  * \return a callback handler that can be used to remove the user callback from list of IR-stream callbacks.
350  */
351  template<typename T> CallbackHandle
352  registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* cookie = NULL) throw ();
353 
354  /** \brief unregisters a callback function. i.e. removes that function from the list of IR stream callbacks.
355  * \param[in] callbackHandle the handle of the callback to unregister.
356  * \return true, if callback was in list and could be unregistered, false otherwise.
357  */
358  bool
359  unregisterIRCallback (const CallbackHandle& callbackHandle) throw ();
360 
361  /** \brief returns the serial number for device.
362  * \attention This might be an empty string!!!
363  */
364  const char*
365  getSerialNumber () const throw ();
366 
367  /** \brief returns the connection string for current device, which has following format vendorID/productID\@BusID/DeviceID. */
368  const char*
369  getConnectionString () const throw ();
370 
371  /** \return the Vendor name of the USB device. */
372  const char*
373  getVendorName () const throw ();
374 
375  /** \return the product name of the USB device. */
376  const char*
377  getProductName () const throw ();
378 
379  /** \return the vendor ID of the USB device. */
380  unsigned short
381  getVendorID () const throw ();
382 
383  /** \return the product ID of the USB device. */
384  unsigned short
385  getProductID () const throw ();
386 
387  /** \return the USB bus on which the device is connected. */
388  unsigned char
389  getBus () const throw ();
390 
391  /** \return the USB Address of the device. */
392  unsigned char
393  getAddress () const throw ();
394 
395  /** \brief Set the RGB image focal length.
396  * \param[in] focal_length the RGB image focal length
397  */
398  inline void
399  setRGBFocalLength (float focal_length)
400  {
401  rgb_focal_length_SXGA_ = focal_length;
402  }
403 
404  /** \brief Set the depth image focal length.
405  * \param[in] focal_length the depth image focal length
406  */
407  inline void
408  setDepthFocalLength (float focal_length)
409  {
410  depth_focal_length_SXGA_ = focal_length;
411  }
412 
413  /** \brief Set the depth output format. Use 12bit depth values or shift values.
414  * \param[in] depth_mode the depth output format
415  */
416  void
417  setDepthOutputFormat (const DepthMode& depth_mode = OpenNI_12_bit_depth);
418 
419  /** \brief Get the depth output format as set by the user. */
420  XnUInt64
421  getDepthOutputFormat () const;
422 
423 
424  /** \brief Convert shift to depth value. */
425  pcl::uint16_t
426  shiftToDepth (pcl::uint16_t shift_value) const
427  {
428  assert (shift_conversion_parameters_.init_);
429 
430  pcl::uint16_t ret = 0;
431 
432  // lookup depth value in shift lookup table
433  if (shift_value<shift_to_depth_table_.size())
434  ret = shift_to_depth_table_[shift_value];
435 
436  return ret;
437  }
438 
439  private:
440  // make OpenNIDevice non copyable
441  OpenNIDevice (OpenNIDevice const &);
442  OpenNIDevice& operator=(OpenNIDevice const &);
443  protected:
444  typedef boost::function<void(boost::shared_ptr<Image>) > ActualImageCallbackFunction;
445  typedef boost::function<void(boost::shared_ptr<DepthImage>) > ActualDepthImageCallbackFunction;
446  typedef boost::function<void(boost::shared_ptr<IRImage>) > ActualIRImageCallbackFunction;
447 
448  OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node);
449  OpenNIDevice (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node);
450  OpenNIDevice (xn::Context& context);
451  static void __stdcall NewDepthDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
452  static void __stdcall NewImageDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
453  static void __stdcall NewIRDataAvailable (xn::ProductionNode& node, void* cookie) throw ();
454 
455  // This is a workaround, since in the NewDepthDataAvailable function WaitAndUpdateData leads to a dead-lock behaviour
456  // and retrieving image data without WaitAndUpdateData leads to incomplete images!!!
457  void
458  ImageDataThreadFunction ();
459 
460  void
461  DepthDataThreadFunction ();
462 
463  void
464  IRDataThreadFunction ();
465 
466  virtual bool
467  isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () = 0;
468 
469  void
470  setRegistration (bool on_off);
471 
472  virtual boost::shared_ptr<Image>
473  getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () = 0;
474 
475  void
476  Init ();
477 
478  void InitShiftToDepthConversion();
479  void ReadDeviceParametersFromSensorNode();
480 
482  {
483  ShiftConversion() : init_(false) {}
484 
488  XnUInt32 max_shift_;
490  XnUInt32 const_shift_;
492  XnUInt32 param_coeff_;
493  XnUInt32 shift_scale_;
494  XnUInt32 min_depth_;
495  XnUInt32 max_depth_;
496  bool init_;
497 
498  } shift_conversion_parameters_;
499 
500  std::vector<pcl::uint16_t> shift_to_depth_table_;
501 
502  // holds the callback functions together with custom data
503  // since same callback function can be registered multiple times with e.g. different custom data
504  // we use a map structure with a handle as the key
505  std::map<CallbackHandle, ActualImageCallbackFunction> image_callback_;
506  std::map<CallbackHandle, ActualDepthImageCallbackFunction> depth_callback_;
507  std::map<CallbackHandle, ActualIRImageCallbackFunction> ir_callback_;
508 
509  std::vector<XnMapOutputMode> available_image_modes_;
510  std::vector<XnMapOutputMode> available_depth_modes_;
511 
512  /** \brief context to OpenNI driver*/
513  xn::Context& context_;
514  /** \brief node object for current device */
515  xn::NodeInfo device_node_info_;
516 
517  /** \brief Depth generator object. */
518  xn::DepthGenerator depth_generator_;
519  /** \brief Image generator object. */
520  xn::ImageGenerator image_generator_;
521  /** \brief IR generator object. */
522  xn::IRGenerator ir_generator_;
523 
524  XnCallbackHandle depth_callback_handle_;
525  XnCallbackHandle image_callback_handle_;
526  XnCallbackHandle ir_callback_handle_;
527 
528  /** \brief focal length for IR camera producing depth information in native SXGA mode */
530  /** \brief distance between the projector and the IR camera*/
531  float baseline_;
532  /** \brief focal length for regular camera producing color images in native SXGA mode */
534 
535  /** the value for shadow (occluded pixels) */
536  XnUInt64 shadow_value_;
537  /** the value for pixels without a valid disparity measurement */
539 
543 
544  bool quit_;
545  mutable boost::mutex image_mutex_;
546  mutable boost::mutex depth_mutex_;
547  mutable boost::mutex ir_mutex_;
548  boost::condition_variable image_condition_;
549  boost::condition_variable depth_condition_;
550  boost::condition_variable ir_condition_;
551  boost::thread image_thread_;
552  boost::thread depth_thread_;
553  boost::thread ir_thread_;
554  };
555 
556  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
557  float
558  OpenNIDevice::getImageFocalLength (int output_x_resolution) const throw ()
559  {
560  if (output_x_resolution == 0)
561  output_x_resolution = getImageOutputMode ().nXRes;
562 
563  float scale = static_cast<float> (output_x_resolution) / static_cast<float> (XN_SXGA_X_RES);
564  return (rgb_focal_length_SXGA_ * scale);
565  }
566 
567  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
568  float
569  OpenNIDevice::getDepthFocalLength (int output_x_resolution) const throw ()
570  {
571  if (output_x_resolution == 0)
572  output_x_resolution = getDepthOutputMode ().nXRes;
573 
574  float scale = static_cast<float> (output_x_resolution) / static_cast<float> (XN_SXGA_X_RES);
575  if (isDepthRegistered ())
576  return (rgb_focal_length_SXGA_ * scale);
577  else
578  return (depth_focal_length_SXGA_ * scale);
579  }
580 
581  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
582  float
583  OpenNIDevice::getBaseline () const throw ()
584  {
585  return (baseline_);
586  }
587 
588  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
589  template<typename T> OpenNIDevice::CallbackHandle
590  OpenNIDevice::registerImageCallback (void (T::*callback)(boost::shared_ptr<Image>, void* cookie), T& instance, void* custom_data) throw ()
591  {
592  image_callback_[image_callback_handle_counter_] = boost::bind (callback, boost::ref (instance), _1, custom_data);
593  return (image_callback_handle_counter_++);
594  }
595 
596  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
597  template<typename T> OpenNIDevice::CallbackHandle
598  OpenNIDevice::registerDepthCallback (void (T::*callback)(boost::shared_ptr<DepthImage>, void* cookie), T& instance, void* custom_data) throw ()
599  {
600  depth_callback_[depth_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data);
601  return (depth_callback_handle_counter_++);
602  }
603 
604  ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
605  template<typename T> OpenNIDevice::CallbackHandle
606  OpenNIDevice::registerIRCallback (void (T::*callback)(boost::shared_ptr<IRImage>, void* cookie), T& instance, void* custom_data) throw ()
607  {
608  ir_callback_[ir_callback_handle_counter_] = boost::bind ( callback, boost::ref (instance), _1, custom_data);
609  return (ir_callback_handle_counter_++);
610  }
611 
612 }
613 #endif // __OPENNI_IDEVICE_H__
614 #endif // HAVE_OPENNI
boost::function< void(boost::shared_ptr< IRImage >) > ActualIRImageCallbackFunction
std::vector< XnMapOutputMode > available_depth_modes_
CallbackHandle registerImageCallback(const ImageCallbackFunction &callback, void *cookie=NULL)
registers a callback function of boost::function type for the image stream with an optional user defi...
DeviceArray2D< uchar4 > Image
Definition: label_common.h:113
CallbackHandle registerDepthCallback(const DepthImageCallbackFunction &callback, void *cookie=NULL)
registers a callback function of boost::function type for the depth stream with an optional user defi...
float getImageFocalLength(int output_x_resolution=0) const
returns the focal length for the color camera in pixels.
boost::function< void(boost::shared_ptr< Image >) > ActualImageCallbackFunction
std::map< CallbackHandle, ActualImageCallbackFunction > image_callback_
Class representing an astract device for OpenNI devices: Primesense PSDK, Microsoft Kinect...
Definition: openni_device.h:69
xn::ImageGenerator image_generator_
Image generator object.
XnUInt64 no_sample_value_
the value for pixels without a valid disparity measurement
std::vector< XnMapOutputMode > available_image_modes_
void setDepthFocalLength(float focal_length)
Set the depth image focal length.
Image class containing just a reference to image meta data.
Definition: openni_image.h:58
OpenNIDevice::CallbackHandle ir_callback_handle_counter_
boost::function< void(boost::shared_ptr< DepthImage >, void *cookie) > DepthImageCallbackFunction
Definition: openni_device.h:79
float baseline_
distance between the projector and the IR camera
xn::Context & context_
context to OpenNI driver
OpenNIDevice::CallbackHandle depth_callback_handle_counter_
boost::condition_variable ir_condition_
pcl::io::DepthImage DepthImage
This class provides methods to fill a depth or disparity image.
boost::condition_variable image_condition_
CallbackHandle registerIRCallback(const IRImageCallbackFunction &callback, void *cookie=NULL)
registers a callback function of boost::function type for the IR stream with an optional user defined...
xn::IRGenerator ir_generator_
IR generator object.
boost::function< void(boost::shared_ptr< DepthImage >) > ActualDepthImageCallbackFunction
XnCallbackHandle depth_callback_handle_
boost::function< void(boost::shared_ptr< Image >, void *cookie) > ImageCallbackFunction
Definition: openni_device.h:78
boost::function< void(boost::shared_ptr< IRImage >, void *cookie) > IRImageCallbackFunction
Definition: openni_device.h:80
std::vector< pcl::uint16_t > shift_to_depth_table_
xn::NodeInfo device_node_info_
node object for current device
pcl::uint16_t shiftToDepth(pcl::uint16_t shift_value) const
Convert shift to depth value.
OpenNIDevice::CallbackHandle image_callback_handle_counter_
float rgb_focal_length_SXGA_
focal length for regular camera producing color images in native SXGA mode
std::map< CallbackHandle, ActualDepthImageCallbackFunction > depth_callback_
std::map< CallbackHandle, ActualIRImageCallbackFunction > ir_callback_
boost::condition_variable depth_condition_
XnCallbackHandle ir_callback_handle_
float getDepthFocalLength(int output_x_resolution=0) const
returns the focal length for the IR camera in pixels.
xn::DepthGenerator depth_generator_
Depth generator object.
float depth_focal_length_SXGA_
focal length for IR camera producing depth information in native SXGA mode
Class containing just a reference to IR meta data.
pcl::io::IRImage IRImage
XnCallbackHandle image_callback_handle_
XnUInt64 shadow_value_
the value for shadow (occluded pixels)