41 #include <pcl/pcl_config.h>
48 #include <pcl/pcl_exports.h>
49 #include "openni_exception.h"
59 using Ptr = pcl::shared_ptr<DepthImage>;
60 using ConstPtr = pcl::shared_ptr<const DepthImage>;
71 inline DepthImage (pcl::shared_ptr<xn::DepthMetaData> depth_meta_data,
float baseline,
float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) noexcept;
79 inline const xn::DepthMetaData&
80 getDepthMetaData () const throw ();
90 fillDisparityImage (
unsigned width,
unsigned height,
float* disparity_buffer,
unsigned line_step = 0) const;
100 fillDepthImage (
unsigned width,
unsigned height,
float* depth_buffer,
unsigned line_step = 0) const;
110 fillDepthImageRaw (
unsigned width,
unsigned height,
unsigned short* depth_buffer,
unsigned line_step = 0) const;
116 getBaseline () const throw ();
122 getFocalLength () const throw ();
128 getShadowValue () const throw ();
134 getNoSampleValue () const throw ();
138 getWidth () const throw ();
142 getHeight () const throw ();
148 getFrameID () const throw ();
155 getTimeStamp () const throw ();
158 pcl::shared_ptr<xn::DepthMetaData> depth_md_;
161 XnUInt64 shadow_value_;
162 XnUInt64 no_sample_value_;
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) { }
174 const xn::DepthMetaData&
189 return focal_length_;
195 return shadow_value_;
201 return no_sample_value_;
207 return depth_md_->XRes ();
213 return depth_md_->YRes ();
219 return depth_md_->FrameID ();
225 return static_cast<unsigned long> (depth_md_->Timestamp ());