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