Point Cloud Library (PCL)  1.14.1-dev
openni_depth_image.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 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/memory.h>
43 #ifdef HAVE_OPENNI
44 
45 #include "openni.h"
46 
47 //#include <pcl/pcl_macros.h> // <-- because current header is included in NVCC-compiled code and contains <Eigen/Core>. Consider <pcl/pcl_exports.h>
48 #include <pcl/pcl_exports.h>
49 #include "openni_exception.h"
50 
51 namespace openni_wrapper
52 {
53  /** \brief This class provides methods to fill a depth or disparity image.
54  * \author Suat Gedikli
55  */
57  {
58  public:
59  using Ptr = pcl::shared_ptr<DepthImage>;
60  using ConstPtr = pcl::shared_ptr<const DepthImage>;
61 
62  /** \brief Constructor
63  * \param[in] depth_meta_data the actual data from the OpenNI library
64  * \param[in] baseline the baseline of the "stereo" camera, i.e. the distance between the projector and the IR camera for
65  * Primesense like cameras. e.g. 7.5cm for PSDK5 and PSDK6 reference design.
66  * \param[in] focal_length focal length of the "stereo" frame.
67  * \param[in] shadow_value defines which values in the depth data are indicating shadow (resulting from the parallax between projector and IR camera)
68  * \param[in] no_sample_value defines which values in the depth data are indicating that no depth (disparity) could be determined .
69  * \attention The focal length may change, depending whether the depth stream is registered/mapped to the RGB stream or not.
70  */
71  inline DepthImage (pcl::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) noexcept;
72 
73  /** \brief Destructor. Never throws an exception. */
74  inline virtual ~DepthImage () noexcept;
75 
76  /** \brief method to access the internal data structure from OpenNI. If the data is accessed just read-only, then this method is faster than a fillXXX method
77  * \return the actual depth data of type xn::DepthMetaData.
78  */
79  inline const xn::DepthMetaData&
80  getDepthMetaData () const noexcept;
81 
82  /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling.
83  * \param[in] width the width of the desired disparity image.
84  * \param[in] height the height of the desired disparity image.
85  * \param[in,out] disparity_buffer the float pointer to the actual memory buffer to be filled with the disparity values.
86  * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the
87  * width in bytes (not floats) of the original width of the depth buffer.
88  */
89  void
90  fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const;
91 
92  /** \brief fills a user given block of memory with the disparity values with additional nearest-neighbor down-scaling.
93  * \param[in] width width the width of the desired depth image.
94  * \param[in] height height the height of the desired depth image.
95  * \param[in,out] depth_buffer the float pointer to the actual memory buffer to be filled with the depth values.
96  * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the
97  * width in bytes (not floats) of the original width of the depth buffer.
98  */
99  void
100  fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const;
101 
102  /** \brief fills a user given block of memory with the raw values with additional nearest-neighbor down-scaling.
103  * \param[in] width width the width of the desired raw image.
104  * \param[in] height height the height of the desired raw image.
105  * \param[in,out] depth_buffer the unsigned short pointer to the actual memory buffer to be filled with the raw values.
106  * \param[in] line_step if only a rectangular sub region of the buffer needs to be filled, then line_step is the
107  * width in bytes (not floats) of the original width of the depth buffer.
108  */
109  void
110  fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const;
111 
112  /** \brief method to access the baseline of the "stereo" frame that was used to retrieve the depth image.
113  * \return baseline in meters
114  */
115  inline float
116  getBaseline () const noexcept;
117 
118  /** \brief method to access the focal length of the "stereo" frame that was used to retrieve the depth image.
119  * \return focal length in pixels
120  */
121  inline float
122  getFocalLength () const noexcept;
123 
124  /** \brief method to access the shadow value, that indicates pixels lying in shadow in the depth image.
125  * \return shadow value
126  */
127  inline XnUInt64
128  getShadowValue () const noexcept;
129 
130  /** \brief method to access the no-sample value, that indicates pixels where no disparity could be determined for the depth image.
131  * \return no-sample value
132  */
133  inline XnUInt64
134  getNoSampleValue () const noexcept;
135 
136  /** \return the width of the depth image */
137  inline unsigned
138  getWidth () const noexcept;
139 
140  /** \return the height of the depth image */
141  inline unsigned
142  getHeight () const noexcept;
143 
144  /** \return an ascending id for the depth frame
145  * \attention not necessarily synchronized with other streams
146  */
147  inline unsigned
148  getFrameID () const noexcept;
149 
150  /** \return a ascending timestamp for the depth frame
151  * \attention its not the system time, thus can not be used directly to synchronize different sensors.
152  * But definitely synchronized with other streams
153  */
154  inline unsigned long
155  getTimeStamp () const noexcept;
156 
157  protected:
158  pcl::shared_ptr<xn::DepthMetaData> depth_md_;
159  float baseline_;
160  float focal_length_;
161  XnUInt64 shadow_value_;
162  XnUInt64 no_sample_value_;
163  } ;
164 
165  DepthImage::DepthImage (pcl::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) noexcept
166  : depth_md_ (std::move(depth_meta_data))
167  , baseline_ (baseline)
168  , focal_length_ (focal_length)
169  , shadow_value_ (shadow_value)
170  , no_sample_value_ (no_sample_value) { }
171 
172  DepthImage::~DepthImage () noexcept = default;
173 
174  const xn::DepthMetaData&
175  DepthImage::getDepthMetaData () const noexcept
176  {
177  return *depth_md_;
178  }
179 
180  float
181  DepthImage::getBaseline () const noexcept
182  {
183  return baseline_;
184  }
185 
186  float
187  DepthImage::getFocalLength () const noexcept
188  {
189  return focal_length_;
190  }
191 
192  XnUInt64
193  DepthImage::getShadowValue () const noexcept
194  {
195  return shadow_value_;
196  }
197 
198  XnUInt64
200  {
201  return no_sample_value_;
202  }
203 
204  unsigned
205  DepthImage::getWidth () const noexcept
206  {
207  return depth_md_->XRes ();
208  }
209 
210  unsigned
211  DepthImage::getHeight () const noexcept
212  {
213  return depth_md_->YRes ();
214  }
215 
216  unsigned
217  DepthImage::getFrameID () const noexcept
218  {
219  return depth_md_->FrameID ();
220  }
221 
222  unsigned long
223  DepthImage::getTimeStamp () const noexcept
224  {
225  return static_cast<unsigned long> (depth_md_->Timestamp ());
226  }
227 } // namespace
228 #endif
This class provides methods to fill a depth or disparity image.
unsigned getFrameID() const noexcept
pcl::shared_ptr< DepthImage > Ptr
XnUInt64 getShadowValue() const noexcept
method to access the shadow value, that indicates pixels lying in shadow in the depth image.
pcl::shared_ptr< const DepthImage > ConstPtr
XnUInt64 getNoSampleValue() const noexcept
method to access the no-sample value, that indicates pixels where no disparity could be determined fo...
unsigned getWidth() const noexcept
float getBaseline() const noexcept
method to access the baseline of the "stereo" frame that was used to retrieve the depth image.
virtual ~DepthImage() noexcept
Destructor.
unsigned getHeight() const noexcept
unsigned long getTimeStamp() const noexcept
float getFocalLength() const noexcept
method to access the focal length of the "stereo" frame that was used to retrieve the depth image.
Defines functions, macros and traits for allocating and using memory.
#define PCL_EXPORTS
Definition: pcl_macros.h:323