Point Cloud Library (PCL)  1.9.1-dev
openni_grabber.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  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  */
38 
39 #pragma once
40 
41 #include <pcl/pcl_config.h>
42 #include <pcl/pcl_macros.h>
43 
44 #ifdef HAVE_OPENNI
45 
46 #include <pcl/point_cloud.h>
47 #include <pcl/io/eigen.h>
48 #include <pcl/io/boost.h>
49 #include <pcl/io/grabber.h>
50 #include <pcl/io/openni_camera/openni_driver.h>
51 #include <pcl/io/openni_camera/openni_device_kinect.h>
52 #include <pcl/io/openni_camera/openni_image.h>
53 #include <pcl/io/openni_camera/openni_depth_image.h>
54 #include <pcl/io/openni_camera/openni_ir_image.h>
55 #include <string>
56 #include <deque>
57 #include <pcl/common/synchronizer.h>
58 
59 namespace pcl
60 {
61  struct PointXYZ;
62  struct PointXYZRGB;
63  struct PointXYZRGBA;
64  struct PointXYZI;
65 
66  /** \brief Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live)
67  * \author Nico Blodow <blodow@cs.tum.edu>, Suat Gedikli <gedikli@willowgarage.com>
68  * \ingroup io
69  */
70  class PCL_EXPORTS OpenNIGrabber : public Grabber
71  {
72  public:
73  using Ptr = boost::shared_ptr<OpenNIGrabber>;
74  using ConstPtr = boost::shared_ptr<const OpenNIGrabber>;
75 
76  enum Mode
77  {
78  OpenNI_Default_Mode = 0, // This can depend on the device. For now all devices (PSDK, Xtion, Kinect) its VGA@30Hz
79  OpenNI_SXGA_15Hz = 1, // Only supported by the Kinect
80  OpenNI_VGA_30Hz = 2, // Supported by PSDK, Xtion and Kinect
81  OpenNI_VGA_25Hz = 3, // Supportged by PSDK and Xtion
82  OpenNI_QVGA_25Hz = 4, // Supported by PSDK and Xtion
83  OpenNI_QVGA_30Hz = 5, // Supported by PSDK, Xtion and Kinect
84  OpenNI_QVGA_60Hz = 6, // Supported by PSDK and Xtion
85  OpenNI_QQVGA_25Hz = 7, // Not supported -> using software downsampling (only for integer scale factor and only NN)
86  OpenNI_QQVGA_30Hz = 8, // Not supported -> using software downsampling (only for integer scale factor and only NN)
87  OpenNI_QQVGA_60Hz = 9 // Not supported -> using software downsampling (only for integer scale factor and only NN)
88  };
89 
90  //define callback signature typedefs
100 
101  public:
102  /** \brief Constructor
103  * \param[in] device_id ID of the device, which might be a serial number, bus\@address or the index of the device.
104  * \param[in] depth_mode the mode of the depth stream
105  * \param[in] image_mode the mode of the image stream
106  */
107  OpenNIGrabber (const std::string& device_id = "",
108  const Mode& depth_mode = OpenNI_Default_Mode,
109  const Mode& image_mode = OpenNI_Default_Mode);
110 
111  /** \brief virtual Destructor inherited from the Grabber interface. It never throws. */
112  ~OpenNIGrabber () throw ();
113 
114  /** \brief Start the data acquisition. */
115  void
116  start () override;
117 
118  /** \brief Stop the data acquisition. */
119  void
120  stop () override;
121 
122  /** \brief Check if the data acquisition is still running. */
123  bool
124  isRunning () const override;
125 
126  std::string
127  getName () const override;
128 
129  /** \brief Obtain the number of frames per second (FPS). */
130  float
131  getFramesPerSecond () const override;
132 
133  /** \brief Get a boost shared pointer to the \ref pcl::openni_wrapper::OpenNIDevice object. */
134  inline openni_wrapper::OpenNIDevice::Ptr
135  getDevice () const;
136 
137  /** \brief Obtain a list of the available depth modes that this device supports. */
138  std::vector<std::pair<int, XnMapOutputMode> >
139  getAvailableDepthModes () const;
140 
141  /** \brief Obtain a list of the available image modes that this device supports. */
142  std::vector<std::pair<int, XnMapOutputMode> >
143  getAvailableImageModes () const;
144 
145  /** \brief Set the RGB camera parameters (fx, fy, cx, cy)
146  * \param[in] rgb_focal_length_x the RGB focal length (fx)
147  * \param[in] rgb_focal_length_y the RGB focal length (fy)
148  * \param[in] rgb_principal_point_x the RGB principal point (cx)
149  * \param[in] rgb_principal_point_y the RGB principal point (cy)
150  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
151  * and the grabber will use the default values from the camera instead.
152  */
153  inline void
154  setRGBCameraIntrinsics (const double rgb_focal_length_x,
155  const double rgb_focal_length_y,
156  const double rgb_principal_point_x,
157  const double rgb_principal_point_y)
158  {
159  rgb_focal_length_x_ = rgb_focal_length_x;
160  rgb_focal_length_y_ = rgb_focal_length_y;
161  rgb_principal_point_x_ = rgb_principal_point_x;
162  rgb_principal_point_y_ = rgb_principal_point_y;
163  }
164 
165  /** \brief Get the RGB camera parameters (fx, fy, cx, cy)
166  * \param[out] rgb_focal_length_x the RGB focal length (fx)
167  * \param[out] rgb_focal_length_y the RGB focal length (fy)
168  * \param[out] rgb_principal_point_x the RGB principal point (cx)
169  * \param[out] rgb_principal_point_y the RGB principal point (cy)
170  */
171  inline void
172  getRGBCameraIntrinsics (double &rgb_focal_length_x,
173  double &rgb_focal_length_y,
174  double &rgb_principal_point_x,
175  double &rgb_principal_point_y) const
176  {
177  rgb_focal_length_x = rgb_focal_length_x_;
178  rgb_focal_length_y = rgb_focal_length_y_;
179  rgb_principal_point_x = rgb_principal_point_x_;
180  rgb_principal_point_y = rgb_principal_point_y_;
181  }
182 
183 
184  /** \brief Set the RGB image focal length (fx = fy).
185  * \param[in] rgb_focal_length the RGB focal length (assumes fx = fy)
186  * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it
187  * and the grabber will use the default values from the camera instead.
188  * These parameters will be used for XYZRGBA clouds.
189  */
190  inline void
191  setRGBFocalLength (const double rgb_focal_length)
192  {
193  rgb_focal_length_x_ = rgb_focal_length_y_ = rgb_focal_length;
194  }
195 
196  /** \brief Set the RGB image focal length
197  * \param[in] rgb_focal_length_x the RGB focal length (fx)
198  * \param[in] rgb_focal_length_y the RGB focal length (fy)
199  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
200  * and the grabber will use the default values from the camera instead.
201  * These parameters will be used for XYZRGBA clouds.
202  */
203  inline void
204  setRGBFocalLength (const double rgb_focal_length_x, const double rgb_focal_length_y)
205  {
206  rgb_focal_length_x_ = rgb_focal_length_x;
207  rgb_focal_length_y_ = rgb_focal_length_y;
208  }
209 
210  /** \brief Return the RGB focal length parameters (fx, fy)
211  * \param[out] rgb_focal_length_x the RGB focal length (fx)
212  * \param[out] rgb_focal_length_y the RGB focal length (fy)
213  */
214  inline void
215  getRGBFocalLength (double &rgb_focal_length_x, double &rgb_focal_length_y) const
216  {
217  rgb_focal_length_x = rgb_focal_length_x_;
218  rgb_focal_length_y = rgb_focal_length_y_;
219  }
220 
221  /** \brief Set the Depth camera parameters (fx, fy, cx, cy)
222  * \param[in] depth_focal_length_x the Depth focal length (fx)
223  * \param[in] depth_focal_length_y the Depth focal length (fy)
224  * \param[in] depth_principal_point_x the Depth principal point (cx)
225  * \param[in] depth_principal_point_y the Depth principal point (cy)
226  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
227  * and the grabber will use the default values from the camera instead.
228  */
229  inline void
230  setDepthCameraIntrinsics (const double depth_focal_length_x,
231  const double depth_focal_length_y,
232  const double depth_principal_point_x,
233  const double depth_principal_point_y)
234  {
235  depth_focal_length_x_ = depth_focal_length_x;
236  depth_focal_length_y_ = depth_focal_length_y;
237  depth_principal_point_x_ = depth_principal_point_x;
238  depth_principal_point_y_ = depth_principal_point_y;
239  }
240 
241  /** \brief Get the Depth camera parameters (fx, fy, cx, cy)
242  * \param[out] depth_focal_length_x the Depth focal length (fx)
243  * \param[out] depth_focal_length_y the Depth focal length (fy)
244  * \param[out] depth_principal_point_x the Depth principal point (cx)
245  * \param[out] depth_principal_point_y the Depth principal point (cy)
246  */
247  inline void
248  getDepthCameraIntrinsics (double &depth_focal_length_x,
249  double &depth_focal_length_y,
250  double &depth_principal_point_x,
251  double &depth_principal_point_y) const
252  {
253  depth_focal_length_x = depth_focal_length_x_;
254  depth_focal_length_y = depth_focal_length_y_;
255  depth_principal_point_x = depth_principal_point_x_;
256  depth_principal_point_y = depth_principal_point_y_;
257  }
258 
259  /** \brief Set the Depth image focal length (fx = fy).
260  * \param[in] depth_focal_length the Depth focal length (assumes fx = fy)
261  * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it
262  * and the grabber will use the default values from the camera instead.
263  */
264  inline void
265  setDepthFocalLength (const double depth_focal_length)
266  {
267  depth_focal_length_x_ = depth_focal_length_y_ = depth_focal_length;
268  }
269 
270 
271  /** \brief Set the Depth image focal length
272  * \param[in] depth_focal_length_x the Depth focal length (fx)
273  * \param[in] depth_focal_length_y the Depth focal length (fy)
274  * Setting the parameter to non-finite values (e.g., NaN, Inf) invalidates them
275  * and the grabber will use the default values from the camera instead.
276  */
277  inline void
278  setDepthFocalLength (const double depth_focal_length_x, const double depth_focal_length_y)
279  {
280  depth_focal_length_x_ = depth_focal_length_x;
281  depth_focal_length_y_ = depth_focal_length_y;
282  }
283 
284  /** \brief Return the Depth focal length parameters (fx, fy)
285  * \param[out] depth_focal_length_x the Depth focal length (fx)
286  * \param[out] depth_focal_length_y the Depth focal length (fy)
287  */
288  inline void
289  getDepthFocalLength (double &depth_focal_length_x, double &depth_focal_length_y) const
290  {
291  depth_focal_length_x = depth_focal_length_x_;
292  depth_focal_length_y = depth_focal_length_y_;
293  }
294 
295  /** \brief Convert vector of raw shift values to depth values
296  * \param[in] shift_data_ptr input shift data
297  * \param[out] depth_data_ptr generated depth data
298  * \param[in] size of shift and depth buffer
299  */
300  inline void
302  const uint16_t* shift_data_ptr,
303  uint16_t* depth_data_ptr,
304  std::size_t size) const
305  {
306  // get openni device instance
307  auto openni_device = this->getDevice ();
308 
309  const uint16_t* shift_data_it = shift_data_ptr;
310  uint16_t* depth_data_it = depth_data_ptr;
311 
312  // shift-to-depth lookup
313  for (std::size_t i=0; i<size; ++i)
314  {
315  *depth_data_it = openni_device->shiftToDepth(*shift_data_it);
316 
317  shift_data_it++;
318  depth_data_it++;
319  }
320 
321  }
322 
323 
324  protected:
325  /** \brief On initialization processing. */
326  void
327  onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
328 
329  /** \brief Sets up an OpenNI device. */
330  void
331  setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
332 
333  /** \brief Update mode maps. */
334  void
335  updateModeMaps ();
336 
337  /** \brief Start synchronization. */
338  void
339  startSynchronization ();
340 
341  /** \brief Stop synchronization. */
342  void
343  stopSynchronization ();
344 
345  /** \brief Map config modes. */
346  bool
347  mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const;
348 
349  // callback methods
350  /** \brief RGB image callback. */
351  virtual void
352  imageCallback (openni_wrapper::Image::Ptr image, void* cookie);
353 
354  /** \brief Depth image callback. */
355  virtual void
356  depthCallback (openni_wrapper::DepthImage::Ptr depth_image, void* cookie);
357 
358  /** \brief IR image callback. */
359  virtual void
360  irCallback (openni_wrapper::IRImage::Ptr ir_image, void* cookie);
361 
362  /** \brief RGB + Depth image callback. */
363  virtual void
364  imageDepthImageCallback (const openni_wrapper::Image::Ptr &image,
365  const openni_wrapper::DepthImage::Ptr &depth_image);
366 
367  /** \brief IR + Depth image callback. */
368  virtual void
369  irDepthImageCallback (const openni_wrapper::IRImage::Ptr &image,
370  const openni_wrapper::DepthImage::Ptr &depth_image);
371 
372  /** \brief Process changed signals. */
373  void
374  signalsChanged () override;
375 
376  // helper methods
377 
378  /** \brief Check if the RGB and Depth images are required to be synchronized or not. */
379  virtual void
380  checkImageAndDepthSynchronizationRequired ();
381 
382  /** \brief Check if the RGB image stream is required or not. */
383  virtual void
384  checkImageStreamRequired ();
385 
386  /** \brief Check if the depth stream is required or not. */
387  virtual void
388  checkDepthStreamRequired ();
389 
390  /** \brief Check if the IR image stream is required or not. */
391  virtual void
392  checkIRStreamRequired ();
393 
394 
395  /** \brief Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>
396  * \param[in] depth the depth image to convert
397  */
399  convertToXYZPointCloud (const openni_wrapper::DepthImage::Ptr &depth) const;
400 
401  /** \brief Convert a Depth + RGB image pair to a pcl::PointCloud<PointT>
402  * \param[in] image the RGB image to convert
403  * \param[in] depth_image the depth image to convert
404  */
405  template <typename PointT> typename pcl::PointCloud<PointT>::Ptr
406  convertToXYZRGBPointCloud (const openni_wrapper::Image::Ptr &image,
407  const openni_wrapper::DepthImage::Ptr &depth_image) const;
408 
409  /** \brief Convert a Depth + Intensity image pair to a pcl::PointCloud<pcl::PointXYZI>
410  * \param[in] image the IR image to convert
411  * \param[in] depth_image the depth image to convert
412  */
414  convertToXYZIPointCloud (const openni_wrapper::IRImage::Ptr &image,
415  const openni_wrapper::DepthImage::Ptr &depth_image) const;
416 
417 
420 
421  /** \brief The actual openni device. */
423 
424  std::string rgb_frame_id_;
425  std::string depth_frame_id_;
426  unsigned image_width_;
427  unsigned image_height_;
428  unsigned depth_width_;
429  unsigned depth_height_;
430 
435 
436  boost::signals2::signal<sig_cb_openni_image>* image_signal_;
437  boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
438  boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
439  boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
440  boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
441  boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
442  boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
443  boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
444  boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
445 
446  struct modeComp
447  {
448 
449  bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode & mode2) const
450  {
451  if (mode1.nXRes < mode2.nXRes)
452  return true;
453  if (mode1.nXRes > mode2.nXRes)
454  return false;
455  if (mode1.nYRes < mode2.nYRes)
456  return true;
457  if (mode1.nYRes > mode2.nYRes)
458  return false;
459  return (mode1.nFPS < mode2.nFPS);
460  }
461  } ;
462  std::map<int, XnMapOutputMode> config2xn_map_;
463 
467  bool running_;
468 
469  mutable unsigned rgb_array_size_;
470  mutable unsigned depth_buffer_size_;
471  mutable boost::shared_array<unsigned char> rgb_array_;
472  mutable boost::shared_array<unsigned short> depth_buffer_;
473  mutable boost::shared_array<unsigned short> ir_buffer_;
474 
475  /** \brief The RGB image focal length (fx). */
477  /** \brief The RGB image focal length (fy). */
479  /** \brief The RGB image principal point (cx). */
481  /** \brief The RGB image principal point (cy). */
483  /** \brief The depth image focal length (fx). */
485  /** \brief The depth image focal length (fy). */
487  /** \brief The depth image principal point (cx). */
489  /** \brief The depth image principal point (cy). */
491 
492  public:
494  };
495 
498  {
499  return device_;
500  }
501 
502 } // namespace pcl
503 #endif // HAVE_OPENNI
boost::shared_array< unsigned short > depth_buffer_
boost::shared_ptr< OpenNIGrabber > Ptr
void setDepthFocalLength(const double depth_focal_length_x, const double depth_focal_length_y)
Set the Depth image focal length.
boost::signals2::signal< sig_cb_openni_ir_depth_image > * ir_depth_image_signal_
void getRGBCameraIntrinsics(double &rgb_focal_length_x, double &rgb_focal_length_y, double &rgb_principal_point_x, double &rgb_principal_point_y) const
Get the RGB camera parameters (fx, fy, cx, cy)
Synchronizer< openni_wrapper::Image::Ptr, openni_wrapper::DepthImage::Ptr > rgb_sync_
std::string depth_frame_id_
double depth_principal_point_y_
The depth image principal point (cy).
void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) sig_cb_openni_point_cloud
Synchronizer< openni_wrapper::IRImage::Ptr, openni_wrapper::DepthImage::Ptr > ir_sync_
double rgb_principal_point_y_
The RGB image principal point (cy).
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
boost::shared_ptr< DepthImage > Ptr
double rgb_focal_length_x_
The RGB image focal length (fx).
boost::signals2::signal< sig_cb_openni_point_cloud > * point_cloud_signal_
boost::shared_ptr< OpenNIDevice > Ptr
Definition: openni_device.h:82
boost::shared_ptr< Image > Ptr
Definition: openni_image.h:61
boost::signals2::signal< sig_cb_openni_ir_image > * ir_image_signal_
openni_wrapper::OpenNIDevice::Ptr device_
The actual openni device.
Grabber interface for PCL 1.x device drivers.
Definition: grabber.h:57
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: pcl_macros.h:344
Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live) ...
void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) sig_cb_openni_point_cloud_i
void(const openni_wrapper::DepthImage::Ptr &) sig_cb_openni_depth_image
boost::signals2::signal< sig_cb_openni_point_cloud_rgba > * point_cloud_rgba_signal_
void(const openni_wrapper::Image::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) sig_cb_openni_image_depth_image
boost::shared_ptr< IRImage > Ptr
void setDepthCameraIntrinsics(const double depth_focal_length_x, const double depth_focal_length_y, const double depth_principal_point_x, const double depth_principal_point_y)
Set the Depth camera parameters (fx, fy, cx, cy)
void setRGBFocalLength(const double rgb_focal_length_x, const double rgb_focal_length_y)
Set the RGB image focal length.
void getRGBFocalLength(double &rgb_focal_length_x, double &rgb_focal_length_y) const
Return the RGB focal length parameters (fx, fy)
void(const openni_wrapper::IRImage::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) sig_cb_openni_ir_depth_image
void getDepthCameraIntrinsics(double &depth_focal_length_x, double &depth_focal_length_y, double &depth_principal_point_x, double &depth_principal_point_y) const
Get the Depth camera parameters (fx, fy, cx, cy)
void setDepthFocalLength(const double depth_focal_length)
Set the Depth image focal length (fx = fy).
boost::signals2::signal< sig_cb_openni_depth_image > * depth_image_signal_
double depth_focal_length_x_
The depth image focal length (fx).
openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle
openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:429
std::map< int, XnMapOutputMode > config2xn_map_
float4 PointXYZRGB
Definition: internal.hpp:60
boost::signals2::signal< sig_cb_openni_image_depth_image > * image_depth_image_signal_
void(const openni_wrapper::Image::Ptr &) sig_cb_openni_image
double rgb_focal_length_y_
The RGB image focal length (fy).
boost::signals2::signal< sig_cb_openni_image > * image_signal_
void setRGBFocalLength(const double rgb_focal_length)
Set the RGB image focal length (fx = fy).
boost::shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:430
boost::shared_array< unsigned short > ir_buffer_
boost::shared_array< unsigned char > rgb_array_
double rgb_principal_point_x_
The RGB image principal point (cx).
boost::shared_ptr< const OpenNIGrabber > ConstPtr
void getDepthFocalLength(double &depth_focal_length_x, double &depth_focal_length_y) const
Return the Depth focal length parameters (fx, fy)
void(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &) sig_cb_openni_point_cloud_rgb
unsigned depth_buffer_size_
double depth_focal_length_y_
The depth image focal length (fy).
std::string rgb_frame_id_
openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle
openni_wrapper::OpenNIDevice::Ptr getDevice() const
Get a boost shared pointer to the pcl::openni_wrapper::OpenNIDevice object.
void convertShiftToDepth(const uint16_t *shift_data_ptr, uint16_t *depth_data_ptr, std::size_t size) const
Convert vector of raw shift values to depth values.
void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &) sig_cb_openni_point_cloud_rgba
void(const openni_wrapper::IRImage::Ptr &) sig_cb_openni_ir_image
boost::signals2::signal< sig_cb_openni_point_cloud_rgb > * point_cloud_rgb_signal_
boost::signals2::signal< sig_cb_openni_point_cloud_i > * point_cloud_i_signal_
double depth_principal_point_x_
The depth image principal point (cx).