Point Cloud Library (PCL)  1.11.0
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/memory.h>
42 #include <pcl/pcl_config.h>
43 #include <pcl/pcl_macros.h>
44 
45 #ifdef HAVE_OPENNI
46 
47 #include <pcl/point_cloud.h>
48 #include <pcl/io/eigen.h>
49 #include <pcl/io/boost.h>
50 #include <pcl/io/grabber.h>
51 #include <pcl/io/openni_camera/openni_driver.h>
52 #include <pcl/io/openni_camera/openni_device_kinect.h>
53 #include <pcl/io/openni_camera/openni_image.h>
54 #include <pcl/io/openni_camera/openni_depth_image.h>
55 #include <pcl/io/openni_camera/openni_ir_image.h>
56 #include <string>
57 #include <deque>
58 #include <pcl/common/synchronizer.h>
59 
60 namespace pcl
61 {
62  struct PointXYZ;
63  struct PointXYZRGB;
64  struct PointXYZRGBA;
65  struct PointXYZI;
66 
67  /** \brief Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live)
68  * \author Nico Blodow <blodow@cs.tum.edu>, Suat Gedikli <gedikli@willowgarage.com>
69  * \ingroup io
70  */
72  {
73  public:
74  using Ptr = shared_ptr<OpenNIGrabber>;
75  using ConstPtr = shared_ptr<const OpenNIGrabber>;
76 
77  enum Mode
78  {
79  OpenNI_Default_Mode = 0, // This can depend on the device. For now all devices (PSDK, Xtion, Kinect) its VGA@30Hz
80  OpenNI_SXGA_15Hz = 1, // Only supported by the Kinect
81  OpenNI_VGA_30Hz = 2, // Supported by PSDK, Xtion and Kinect
82  OpenNI_VGA_25Hz = 3, // Supportged by PSDK and Xtion
83  OpenNI_QVGA_25Hz = 4, // Supported by PSDK and Xtion
84  OpenNI_QVGA_30Hz = 5, // Supported by PSDK, Xtion and Kinect
85  OpenNI_QVGA_60Hz = 6, // Supported by PSDK and Xtion
86  OpenNI_QQVGA_25Hz = 7, // Not supported -> using software downsampling (only for integer scale factor and only NN)
87  OpenNI_QQVGA_30Hz = 8, // Not supported -> using software downsampling (only for integer scale factor and only NN)
88  OpenNI_QQVGA_60Hz = 9 // Not supported -> using software downsampling (only for integer scale factor and only NN)
89  };
90 
91  //define callback signature typedefs
101 
102  public:
103  /** \brief Constructor
104  * \param[in] device_id ID of the device, which might be a serial number, bus\@address or the index of the device.
105  * \param[in] depth_mode the mode of the depth stream
106  * \param[in] image_mode the mode of the image stream
107  */
108  OpenNIGrabber (const std::string& device_id = "",
109  const Mode& depth_mode = OpenNI_Default_Mode,
110  const Mode& image_mode = OpenNI_Default_Mode);
111 
112  /** \brief virtual Destructor inherited from the Grabber interface. It never throws. */
113  ~OpenNIGrabber () noexcept;
114 
115  /** \brief Start the data acquisition. */
116  void
117  start () override;
118 
119  /** \brief Stop the data acquisition. */
120  void
121  stop () override;
122 
123  /** \brief Check if the data acquisition is still running. */
124  bool
125  isRunning () const override;
126 
127  std::string
128  getName () const override;
129 
130  /** \brief Obtain the number of frames per second (FPS). */
131  float
132  getFramesPerSecond () const override;
133 
134  /** \brief Get a pcl::shared pointer to the openni_wrapper::OpenNIDevice object. */
135  inline openni_wrapper::OpenNIDevice::Ptr
136  getDevice () const;
137 
138  /** \brief Obtain a list of the available depth modes that this device supports. */
139  std::vector<std::pair<int, XnMapOutputMode> >
140  getAvailableDepthModes () const;
141 
142  /** \brief Obtain a list of the available image modes that this device supports. */
143  std::vector<std::pair<int, XnMapOutputMode> >
144  getAvailableImageModes () const;
145 
146  /** \brief Set the RGB camera parameters (fx, fy, cx, cy)
147  * \param[in] rgb_focal_length_x the RGB focal length (fx)
148  * \param[in] rgb_focal_length_y the RGB focal length (fy)
149  * \param[in] rgb_principal_point_x the RGB principal point (cx)
150  * \param[in] rgb_principal_point_y the RGB principal point (cy)
151  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
152  * and the grabber will use the default values from the camera instead.
153  */
154  inline void
155  setRGBCameraIntrinsics (const double rgb_focal_length_x,
156  const double rgb_focal_length_y,
157  const double rgb_principal_point_x,
158  const double rgb_principal_point_y)
159  {
160  rgb_focal_length_x_ = rgb_focal_length_x;
161  rgb_focal_length_y_ = rgb_focal_length_y;
162  rgb_principal_point_x_ = rgb_principal_point_x;
163  rgb_principal_point_y_ = rgb_principal_point_y;
164  }
165 
166  /** \brief Get the RGB camera parameters (fx, fy, cx, cy)
167  * \param[out] rgb_focal_length_x the RGB focal length (fx)
168  * \param[out] rgb_focal_length_y the RGB focal length (fy)
169  * \param[out] rgb_principal_point_x the RGB principal point (cx)
170  * \param[out] rgb_principal_point_y the RGB principal point (cy)
171  */
172  inline void
173  getRGBCameraIntrinsics (double &rgb_focal_length_x,
174  double &rgb_focal_length_y,
175  double &rgb_principal_point_x,
176  double &rgb_principal_point_y) const
177  {
178  rgb_focal_length_x = rgb_focal_length_x_;
179  rgb_focal_length_y = rgb_focal_length_y_;
180  rgb_principal_point_x = rgb_principal_point_x_;
181  rgb_principal_point_y = rgb_principal_point_y_;
182  }
183 
184 
185  /** \brief Set the RGB image focal length (fx = fy).
186  * \param[in] rgb_focal_length the RGB focal length (assumes fx = fy)
187  * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it
188  * and the grabber will use the default values from the camera instead.
189  * These parameters will be used for XYZRGBA clouds.
190  */
191  inline void
192  setRGBFocalLength (const double rgb_focal_length)
193  {
194  rgb_focal_length_x_ = rgb_focal_length_y_ = rgb_focal_length;
195  }
196 
197  /** \brief Set the RGB image focal length
198  * \param[in] rgb_focal_length_x the RGB focal length (fx)
199  * \param[in] rgb_focal_length_y the RGB focal length (fy)
200  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
201  * and the grabber will use the default values from the camera instead.
202  * These parameters will be used for XYZRGBA clouds.
203  */
204  inline void
205  setRGBFocalLength (const double rgb_focal_length_x, const double rgb_focal_length_y)
206  {
207  rgb_focal_length_x_ = rgb_focal_length_x;
208  rgb_focal_length_y_ = rgb_focal_length_y;
209  }
210 
211  /** \brief Return the RGB focal length parameters (fx, fy)
212  * \param[out] rgb_focal_length_x the RGB focal length (fx)
213  * \param[out] rgb_focal_length_y the RGB focal length (fy)
214  */
215  inline void
216  getRGBFocalLength (double &rgb_focal_length_x, double &rgb_focal_length_y) const
217  {
218  rgb_focal_length_x = rgb_focal_length_x_;
219  rgb_focal_length_y = rgb_focal_length_y_;
220  }
221 
222  /** \brief Set the Depth camera parameters (fx, fy, cx, cy)
223  * \param[in] depth_focal_length_x the Depth focal length (fx)
224  * \param[in] depth_focal_length_y the Depth focal length (fy)
225  * \param[in] depth_principal_point_x the Depth principal point (cx)
226  * \param[in] depth_principal_point_y the Depth principal point (cy)
227  * Setting the parameters to non-finite values (e.g., NaN, Inf) invalidates them
228  * and the grabber will use the default values from the camera instead.
229  */
230  inline void
231  setDepthCameraIntrinsics (const double depth_focal_length_x,
232  const double depth_focal_length_y,
233  const double depth_principal_point_x,
234  const double depth_principal_point_y)
235  {
236  depth_focal_length_x_ = depth_focal_length_x;
237  depth_focal_length_y_ = depth_focal_length_y;
238  depth_principal_point_x_ = depth_principal_point_x;
239  depth_principal_point_y_ = depth_principal_point_y;
240  }
241 
242  /** \brief Get the Depth camera parameters (fx, fy, cx, cy)
243  * \param[out] depth_focal_length_x the Depth focal length (fx)
244  * \param[out] depth_focal_length_y the Depth focal length (fy)
245  * \param[out] depth_principal_point_x the Depth principal point (cx)
246  * \param[out] depth_principal_point_y the Depth principal point (cy)
247  */
248  inline void
249  getDepthCameraIntrinsics (double &depth_focal_length_x,
250  double &depth_focal_length_y,
251  double &depth_principal_point_x,
252  double &depth_principal_point_y) const
253  {
254  depth_focal_length_x = depth_focal_length_x_;
255  depth_focal_length_y = depth_focal_length_y_;
256  depth_principal_point_x = depth_principal_point_x_;
257  depth_principal_point_y = depth_principal_point_y_;
258  }
259 
260  /** \brief Set the Depth image focal length (fx = fy).
261  * \param[in] depth_focal_length the Depth focal length (assumes fx = fy)
262  * Setting the parameter to a non-finite value (e.g., NaN, Inf) invalidates it
263  * and the grabber will use the default values from the camera instead.
264  */
265  inline void
266  setDepthFocalLength (const double depth_focal_length)
267  {
268  depth_focal_length_x_ = depth_focal_length_y_ = depth_focal_length;
269  }
270 
271 
272  /** \brief Set the Depth image focal length
273  * \param[in] depth_focal_length_x the Depth focal length (fx)
274  * \param[in] depth_focal_length_y the Depth focal length (fy)
275  * Setting the parameter to non-finite values (e.g., NaN, Inf) invalidates them
276  * and the grabber will use the default values from the camera instead.
277  */
278  inline void
279  setDepthFocalLength (const double depth_focal_length_x, const double depth_focal_length_y)
280  {
281  depth_focal_length_x_ = depth_focal_length_x;
282  depth_focal_length_y_ = depth_focal_length_y;
283  }
284 
285  /** \brief Return the Depth focal length parameters (fx, fy)
286  * \param[out] depth_focal_length_x the Depth focal length (fx)
287  * \param[out] depth_focal_length_y the Depth focal length (fy)
288  */
289  inline void
290  getDepthFocalLength (double &depth_focal_length_x, double &depth_focal_length_y) const
291  {
292  depth_focal_length_x = depth_focal_length_x_;
293  depth_focal_length_y = depth_focal_length_y_;
294  }
295 
296  /** \brief Convert vector of raw shift values to depth values
297  * \param[in] shift_data_ptr input shift data
298  * \param[out] depth_data_ptr generated depth data
299  * \param[in] size of shift and depth buffer
300  */
301  inline void
303  const std::uint16_t* shift_data_ptr,
304  std::uint16_t* depth_data_ptr,
305  std::size_t size) const
306  {
307  // get openni device instance
308  auto openni_device = this->getDevice ();
309 
310  const std::uint16_t* shift_data_it = shift_data_ptr;
311  std::uint16_t* depth_data_it = depth_data_ptr;
312 
313  // shift-to-depth lookup
314  for (std::size_t i=0; i<size; ++i)
315  {
316  *depth_data_it = openni_device->shiftToDepth(*shift_data_it);
317 
318  shift_data_it++;
319  depth_data_it++;
320  }
321 
322  }
323 
324 
325  protected:
326  /** \brief On initialization processing. */
327  void
328  onInit (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
329 
330  /** \brief Sets up an OpenNI device. */
331  void
332  setupDevice (const std::string& device_id, const Mode& depth_mode, const Mode& image_mode);
333 
334  /** \brief Update mode maps. */
335  void
336  updateModeMaps ();
337 
338  /** \brief Start synchronization. */
339  void
340  startSynchronization ();
341 
342  /** \brief Stop synchronization. */
343  void
344  stopSynchronization ();
345 
346  /** \brief Map config modes. */
347  bool
348  mapConfigMode2XnMode (int mode, XnMapOutputMode &xnmode) const;
349 
350  // callback methods
351  /** \brief RGB image callback. */
352  virtual void
353  imageCallback (openni_wrapper::Image::Ptr image, void* cookie);
354 
355  /** \brief Depth image callback. */
356  virtual void
357  depthCallback (openni_wrapper::DepthImage::Ptr depth_image, void* cookie);
358 
359  /** \brief IR image callback. */
360  virtual void
361  irCallback (openni_wrapper::IRImage::Ptr ir_image, void* cookie);
362 
363  /** \brief RGB + Depth image callback. */
364  virtual void
365  imageDepthImageCallback (const openni_wrapper::Image::Ptr &image,
366  const openni_wrapper::DepthImage::Ptr &depth_image);
367 
368  /** \brief IR + Depth image callback. */
369  virtual void
370  irDepthImageCallback (const openni_wrapper::IRImage::Ptr &image,
371  const openni_wrapper::DepthImage::Ptr &depth_image);
372 
373  /** \brief Process changed signals. */
374  void
375  signalsChanged () override;
376 
377  // helper methods
378 
379  /** \brief Check if the RGB and Depth images are required to be synchronized or not. */
380  virtual void
381  checkImageAndDepthSynchronizationRequired ();
382 
383  /** \brief Check if the RGB image stream is required or not. */
384  virtual void
385  checkImageStreamRequired ();
386 
387  /** \brief Check if the depth stream is required or not. */
388  virtual void
389  checkDepthStreamRequired ();
390 
391  /** \brief Check if the IR image stream is required or not. */
392  virtual void
393  checkIRStreamRequired ();
394 
395 
396  /** \brief Convert a Depth image to a pcl::PointCloud<pcl::PointXYZ>
397  * \param[in] depth the depth image to convert
398  */
400  convertToXYZPointCloud (const openni_wrapper::DepthImage::Ptr &depth) const;
401 
402  /** \brief Convert a Depth + RGB image pair to a pcl::PointCloud<PointT>
403  * \param[in] image the RGB image to convert
404  * \param[in] depth_image the depth image to convert
405  */
406  template <typename PointT> typename pcl::PointCloud<PointT>::Ptr
407  convertToXYZRGBPointCloud (const openni_wrapper::Image::Ptr &image,
408  const openni_wrapper::DepthImage::Ptr &depth_image) const;
409 
410  /** \brief Convert a Depth + Intensity image pair to a pcl::PointCloud<pcl::PointXYZI>
411  * \param[in] image the IR image to convert
412  * \param[in] depth_image the depth image to convert
413  */
415  convertToXYZIPointCloud (const openni_wrapper::IRImage::Ptr &image,
416  const openni_wrapper::DepthImage::Ptr &depth_image) const;
417 
418 
421 
422  /** \brief The actual openni device. */
424 
425  std::string rgb_frame_id_;
426  std::string depth_frame_id_;
427  unsigned image_width_;
428  unsigned image_height_;
429  unsigned depth_width_;
430  unsigned depth_height_;
431 
436 
437  boost::signals2::signal<sig_cb_openni_image>* image_signal_;
438  boost::signals2::signal<sig_cb_openni_depth_image>* depth_image_signal_;
439  boost::signals2::signal<sig_cb_openni_ir_image>* ir_image_signal_;
440  boost::signals2::signal<sig_cb_openni_image_depth_image>* image_depth_image_signal_;
441  boost::signals2::signal<sig_cb_openni_ir_depth_image>* ir_depth_image_signal_;
442  boost::signals2::signal<sig_cb_openni_point_cloud>* point_cloud_signal_;
443  boost::signals2::signal<sig_cb_openni_point_cloud_i>* point_cloud_i_signal_;
444  boost::signals2::signal<sig_cb_openni_point_cloud_rgb>* point_cloud_rgb_signal_;
445  boost::signals2::signal<sig_cb_openni_point_cloud_rgba>* point_cloud_rgba_signal_;
446 
447  struct modeComp
448  {
449 
450  bool operator () (const XnMapOutputMode& mode1, const XnMapOutputMode & mode2) const
451  {
452  if (mode1.nXRes < mode2.nXRes)
453  return true;
454  if (mode1.nXRes > mode2.nXRes)
455  return false;
456  if (mode1.nYRes < mode2.nYRes)
457  return true;
458  if (mode1.nYRes > mode2.nYRes)
459  return false;
460  return (mode1.nFPS < mode2.nFPS);
461  }
462  } ;
463  std::map<int, XnMapOutputMode> config2xn_map_;
464 
468  bool running_;
469 
470  mutable unsigned rgb_array_size_;
471  mutable unsigned depth_buffer_size_;
472  mutable boost::shared_array<unsigned char> rgb_array_;
473  mutable boost::shared_array<unsigned short> depth_buffer_;
474  mutable boost::shared_array<unsigned short> ir_buffer_;
475 
476  /** \brief The RGB image focal length (fx). */
478  /** \brief The RGB image focal length (fy). */
480  /** \brief The RGB image principal point (cx). */
482  /** \brief The RGB image principal point (cy). */
484  /** \brief The depth image focal length (fx). */
486  /** \brief The depth image focal length (fy). */
488  /** \brief The depth image principal point (cx). */
490  /** \brief The depth image principal point (cy). */
492 
493  public:
495  };
496 
499  {
500  return device_;
501  }
502 
503 } // namespace pcl
504 #endif // HAVE_OPENNI
pcl::OpenNIGrabber::config2xn_map_
std::map< int, XnMapOutputMode > config2xn_map_
Definition: openni_grabber.h:463
pcl::OpenNIGrabber::setRGBFocalLength
void setRGBFocalLength(const double rgb_focal_length)
Set the RGB image focal length (fx = fy).
Definition: openni_grabber.h:192
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl
Definition: convolution.h:46
pcl::OpenNIGrabber::ir_required_
bool ir_required_
Definition: openni_grabber.h:434
pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb
void(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &) sig_cb_openni_point_cloud_rgb
Definition: openni_grabber.h:98
pcl::OpenNIGrabber::setDepthCameraIntrinsics
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)
Definition: openni_grabber.h:231
pcl::OpenNIGrabber::depth_buffer_
boost::shared_array< unsigned short > depth_buffer_
Definition: openni_grabber.h:473
pcl::OpenNIGrabber::point_cloud_rgb_signal_
boost::signals2::signal< sig_cb_openni_point_cloud_rgb > * point_cloud_rgb_signal_
Definition: openni_grabber.h:444
pcl::Synchronizer< openni_wrapper::Image::Ptr, openni_wrapper::DepthImage::Ptr >
openni_wrapper::OpenNIDevice::CallbackHandle
unsigned CallbackHandle
Definition: openni_device.h:88
pcl::OpenNIGrabber::rgb_focal_length_y_
double rgb_focal_length_y_
The RGB image focal length (fy).
Definition: openni_grabber.h:479
pcl::OpenNIGrabber::getDepthCameraIntrinsics
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)
Definition: openni_grabber.h:249
pcl::OpenNIGrabber::depth_focal_length_x_
double depth_focal_length_x_
The depth image focal length (fx).
Definition: openni_grabber.h:485
pcl::OpenNIGrabber::point_cloud_rgba_signal_
boost::signals2::signal< sig_cb_openni_point_cloud_rgba > * point_cloud_rgba_signal_
Definition: openni_grabber.h:445
pcl::OpenNIGrabber::rgb_focal_length_x_
double rgb_focal_length_x_
The RGB image focal length (fx).
Definition: openni_grabber.h:477
pcl::OpenNIGrabber::getDepthFocalLength
void getDepthFocalLength(double &depth_focal_length_x, double &depth_focal_length_y) const
Return the Depth focal length parameters (fx, fy)
Definition: openni_grabber.h:290
pcl::OpenNIGrabber::depth_image_signal_
boost::signals2::signal< sig_cb_openni_depth_image > * depth_image_signal_
Definition: openni_grabber.h:438
openni_wrapper::OpenNIDevice::Ptr
pcl::shared_ptr< OpenNIDevice > Ptr
Definition: openni_device.h:82
pcl::OpenNIGrabber::Mode
Mode
Definition: openni_grabber.h:77
pcl::OpenNIGrabber::depth_required_
bool depth_required_
Definition: openni_grabber.h:433
pcl::uint16_t
std::uint16_t uint16_t
Definition: types.h:56
openni_wrapper
Definition: openni_depth_image.h:52
pcl::OpenNIGrabber::sig_cb_openni_point_cloud_i
void(const pcl::PointCloud< pcl::PointXYZI >::ConstPtr &) sig_cb_openni_point_cloud_i
Definition: openni_grabber.h:100
pcl::Grabber
Grabber interface for PCL 1.x device drivers.
Definition: grabber.h:59
pcl::OpenNIGrabber::ConstPtr
shared_ptr< const OpenNIGrabber > ConstPtr
Definition: openni_grabber.h:75
pcl::OpenNIGrabber::image_signal_
boost::signals2::signal< sig_cb_openni_image > * image_signal_
Definition: openni_grabber.h:437
openni_wrapper::Image::Ptr
pcl::shared_ptr< Image > Ptr
Definition: openni_image.h:62
pcl::OpenNIGrabber::sig_cb_openni_ir_image
void(const openni_wrapper::IRImage::Ptr &) sig_cb_openni_ir_image
Definition: openni_grabber.h:94
pcl::OpenNIGrabber::point_cloud_signal_
boost::signals2::signal< sig_cb_openni_point_cloud > * point_cloud_signal_
Definition: openni_grabber.h:442
pcl::OpenNIGrabber::ir_sync_
Synchronizer< openni_wrapper::IRImage::Ptr, openni_wrapper::DepthImage::Ptr > ir_sync_
Definition: openni_grabber.h:420
pcl::OpenNIGrabber::convertShiftToDepth
void convertShiftToDepth(const std::uint16_t *shift_data_ptr, std::uint16_t *depth_data_ptr, std::size_t size) const
Convert vector of raw shift values to depth values.
Definition: openni_grabber.h:302
pcl::OpenNIGrabber::sig_cb_openni_image
void(const openni_wrapper::Image::Ptr &) sig_cb_openni_image
Definition: openni_grabber.h:92
pcl::OpenNIGrabber::depth_frame_id_
std::string depth_frame_id_
Definition: openni_grabber.h:426
pcl::OpenNIGrabber::image_required_
bool image_required_
Definition: openni_grabber.h:432
pcl::OpenNIGrabber::depth_height_
unsigned depth_height_
Definition: openni_grabber.h:430
pcl::OpenNIGrabber::image_width_
unsigned image_width_
Definition: openni_grabber.h:427
pcl::OpenNIGrabber::sig_cb_openni_depth_image
void(const openni_wrapper::DepthImage::Ptr &) sig_cb_openni_depth_image
Definition: openni_grabber.h:93
pcl::OpenNIGrabber::getRGBFocalLength
void getRGBFocalLength(double &rgb_focal_length_x, double &rgb_focal_length_y) const
Return the RGB focal length parameters (fx, fy)
Definition: openni_grabber.h:216
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::OpenNIGrabber::image_height_
unsigned image_height_
Definition: openni_grabber.h:428
pcl::OpenNIGrabber::depth_focal_length_y_
double depth_focal_length_y_
The depth image focal length (fy).
Definition: openni_grabber.h:487
pcl::OpenNIGrabber::depth_principal_point_x_
double depth_principal_point_x_
The depth image principal point (cx).
Definition: openni_grabber.h:489
pcl::OpenNIGrabber::point_cloud_i_signal_
boost::signals2::signal< sig_cb_openni_point_cloud_i > * point_cloud_i_signal_
Definition: openni_grabber.h:443
pcl::OpenNIGrabber::setDepthFocalLength
void setDepthFocalLength(const double depth_focal_length)
Set the Depth image focal length (fx = fy).
Definition: openni_grabber.h:266
pcl::OpenNIGrabber::getRGBCameraIntrinsics
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)
Definition: openni_grabber.h:173
pcl::OpenNIGrabber::sync_required_
bool sync_required_
Definition: openni_grabber.h:435
pcl::OpenNIGrabber::rgb_principal_point_x_
double rgb_principal_point_x_
The RGB image principal point (cx).
Definition: openni_grabber.h:481
pcl::OpenNIGrabber::ir_depth_image_signal_
boost::signals2::signal< sig_cb_openni_ir_depth_image > * ir_depth_image_signal_
Definition: openni_grabber.h:441
pcl::OpenNIGrabber::modeComp
Definition: openni_grabber.h:447
pcl::device::PointXYZRGB
float4 PointXYZRGB
Definition: internal.hpp:60
pcl::OpenNIGrabber::depth_width_
unsigned depth_width_
Definition: openni_grabber.h:429
pcl::OpenNIGrabber::setDepthFocalLength
void setDepthFocalLength(const double depth_focal_length_x, const double depth_focal_length_y)
Set the Depth image focal length.
Definition: openni_grabber.h:279
pcl::OpenNIGrabber::ir_image_signal_
boost::signals2::signal< sig_cb_openni_ir_image > * ir_image_signal_
Definition: openni_grabber.h:439
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba
void(const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr &) sig_cb_openni_point_cloud_rgba
Definition: openni_grabber.h:99
openni_wrapper::IRImage::Ptr
pcl::shared_ptr< IRImage > Ptr
Definition: openni_ir_image.h:55
openni_wrapper::DepthImage::Ptr
pcl::shared_ptr< DepthImage > Ptr
Definition: openni_depth_image.h:60
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
pcl::OpenNIGrabber::ir_buffer_
boost::shared_array< unsigned short > ir_buffer_
Definition: openni_grabber.h:474
pcl::OpenNIGrabber::device_
openni_wrapper::OpenNIDevice::Ptr device_
The actual openni device.
Definition: openni_grabber.h:423
pcl::OpenNIGrabber::Ptr
shared_ptr< OpenNIGrabber > Ptr
Definition: openni_grabber.h:74
pcl::OpenNIGrabber
Grabber for OpenNI devices (i.e., Primesense PSDK, Microsoft Kinect, Asus XTion Pro/Live)
Definition: openni_grabber.h:71
pcl::OpenNIGrabber::depth_principal_point_y_
double depth_principal_point_y_
The depth image principal point (cy).
Definition: openni_grabber.h:491
pcl::OpenNIGrabber::sig_cb_openni_point_cloud
void(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &) sig_cb_openni_point_cloud
Definition: openni_grabber.h:97
pcl::OpenNIGrabber::depth_callback_handle
openni_wrapper::OpenNIDevice::CallbackHandle depth_callback_handle
Definition: openni_grabber.h:465
pcl::OpenNIGrabber::running_
bool running_
Definition: openni_grabber.h:468
pcl::OpenNIGrabber::rgb_sync_
Synchronizer< openni_wrapper::Image::Ptr, openni_wrapper::DepthImage::Ptr > rgb_sync_
Definition: openni_grabber.h:419
pcl::OpenNIGrabber::rgb_array_
boost::shared_array< unsigned char > rgb_array_
Definition: openni_grabber.h:472
pcl::OpenNIGrabber::setRGBFocalLength
void setRGBFocalLength(const double rgb_focal_length_x, const double rgb_focal_length_y)
Set the RGB image focal length.
Definition: openni_grabber.h:205
pcl::OpenNIGrabber::rgb_array_size_
unsigned rgb_array_size_
Definition: openni_grabber.h:470
pcl::OpenNIGrabber::image_callback_handle
openni_wrapper::OpenNIDevice::CallbackHandle image_callback_handle
Definition: openni_grabber.h:466
pcl::OpenNIGrabber::rgb_principal_point_y_
double rgb_principal_point_y_
The RGB image principal point (cy).
Definition: openni_grabber.h:483
pcl::OpenNIGrabber::getDevice
openni_wrapper::OpenNIDevice::Ptr getDevice() const
Get a pcl::shared pointer to the openni_wrapper::OpenNIDevice object.
Definition: openni_grabber.h:498
pcl::OpenNIGrabber::image_depth_image_signal_
boost::signals2::signal< sig_cb_openni_image_depth_image > * image_depth_image_signal_
Definition: openni_grabber.h:440
memory.h
Defines functions, macros and traits for allocating and using memory.
pcl::OpenNIGrabber::depth_buffer_size_
unsigned depth_buffer_size_
Definition: openni_grabber.h:471
PCL_EXPORTS
#define PCL_EXPORTS
Definition: pcl_macros.h:331
pcl::OpenNIGrabber::rgb_frame_id_
std::string rgb_frame_id_
Definition: openni_grabber.h:425
pcl::OpenNIGrabber::ir_callback_handle
openni_wrapper::OpenNIDevice::CallbackHandle ir_callback_handle
Definition: openni_grabber.h:467
pcl::OpenNIGrabber::sig_cb_openni_image_depth_image
void(const openni_wrapper::Image::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) sig_cb_openni_image_depth_image
Definition: openni_grabber.h:95
pcl::OpenNIGrabber::sig_cb_openni_ir_depth_image
void(const openni_wrapper::IRImage::Ptr &, const openni_wrapper::DepthImage::Ptr &, float) sig_cb_openni_ir_depth_image
Definition: openni_grabber.h:96