Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <pcl/pcl_config.h>
00039 #ifdef HAVE_OPENNI
00040
00041 #ifndef __OPENNI_DEPTH_IMAGE__
00042 #define __OPENNI_DEPTH_IMAGE__
00043
00044 #include "openni.h"
00045
00046
00047 #include <pcl/pcl_exports.h>
00048 #include "openni_exception.h"
00049 #include <pcl/io/boost.h>
00050
00051 namespace openni_wrapper
00052 {
00056 class PCL_EXPORTS DepthImage
00057 {
00058 public:
00059 typedef boost::shared_ptr<DepthImage> Ptr;
00060 typedef boost::shared_ptr<const DepthImage> ConstPtr;
00061
00071 inline DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ();
00072
00074 inline virtual ~DepthImage () throw ();
00075
00079 inline const xn::DepthMetaData&
00080 getDepthMetaData () const throw ();
00081
00089 void
00090 fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const;
00091
00099 void
00100 fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const;
00101
00109 void
00110 fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const;
00111
00115 inline float
00116 getBaseline () const throw ();
00117
00121 inline float
00122 getFocalLength () const throw ();
00123
00127 inline XnUInt64
00128 getShadowValue () const throw ();
00129
00133 inline XnUInt64
00134 getNoSampleValue () const throw ();
00135
00137 inline unsigned
00138 getWidth () const throw ();
00139
00141 inline unsigned
00142 getHeight () const throw ();
00143
00147 inline unsigned
00148 getFrameID () const throw ();
00149
00154 inline unsigned long
00155 getTimeStamp () const throw ();
00156
00157 protected:
00158 boost::shared_ptr<xn::DepthMetaData> depth_md_;
00159 float baseline_;
00160 float focal_length_;
00161 XnUInt64 shadow_value_;
00162 XnUInt64 no_sample_value_;
00163 } ;
00164
00165 DepthImage::DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ()
00166 : depth_md_ (depth_meta_data)
00167 , baseline_ (baseline)
00168 , focal_length_ (focal_length)
00169 , shadow_value_ (shadow_value)
00170 , no_sample_value_ (no_sample_value) { }
00171
00172 DepthImage::~DepthImage () throw () { }
00173
00174 const xn::DepthMetaData&
00175 DepthImage::getDepthMetaData () const throw ()
00176 {
00177 return *depth_md_;
00178 }
00179
00180 float
00181 DepthImage::getBaseline () const throw ()
00182 {
00183 return baseline_;
00184 }
00185
00186 float
00187 DepthImage::getFocalLength () const throw ()
00188 {
00189 return focal_length_;
00190 }
00191
00192 XnUInt64
00193 DepthImage::getShadowValue () const throw ()
00194 {
00195 return shadow_value_;
00196 }
00197
00198 XnUInt64
00199 DepthImage::getNoSampleValue () const throw ()
00200 {
00201 return no_sample_value_;
00202 }
00203
00204 unsigned
00205 DepthImage::getWidth () const throw ()
00206 {
00207 return depth_md_->XRes ();
00208 }
00209
00210 unsigned
00211 DepthImage::getHeight () const throw ()
00212 {
00213 return depth_md_->YRes ();
00214 }
00215
00216 unsigned
00217 DepthImage::getFrameID () const throw ()
00218 {
00219 return depth_md_->FrameID ();
00220 }
00221
00222 unsigned long
00223 DepthImage::getTimeStamp () const throw ()
00224 {
00225 return static_cast<unsigned long> (depth_md_->Timestamp ());
00226 }
00227 }
00228 #endif
00229 #endif //__OPENNI_DEPTH_IMAGE