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 #include <pcl/pcl_config.h>
00037 #ifdef HAVE_OPENNI
00038
00039 #ifndef __OPENNI_DEPTH_IMAGE__
00040 #define __OPENNI_DEPTH_IMAGE__
00041
00042 #include <XnCppWrapper.h>
00043
00044
00045 #include <pcl/pcl_exports.h>
00046 #include "openni_exception.h"
00047 #include <boost/shared_ptr.hpp>
00048
00049 namespace openni_wrapper
00050 {
00051
00057 class PCL_EXPORTS DepthImage
00058 {
00059 public:
00060 typedef boost::shared_ptr<DepthImage> Ptr;
00061 typedef boost::shared_ptr<const DepthImage> ConstPtr;
00062
00074 inline DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ();
00075
00080 inline virtual ~DepthImage () throw ();
00081
00087 inline const xn::DepthMetaData& getDepthMetaData () const throw ();
00088
00098 void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const;
00099
00109 void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const;
00110
00120 void fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const;
00121
00127 inline float getBaseline () const throw ();
00128
00134 inline float getFocalLength () const throw ();
00135
00141 inline XnUInt64 getShadowValue () const throw ();
00142
00148 inline XnUInt64 getNoSampleValue () const throw ();
00149
00154 inline unsigned getWidth () const throw ();
00155
00160 inline unsigned getHeight () const throw ();
00161
00167 inline unsigned getFrameID () const throw ();
00168
00175 inline unsigned long getTimeStamp () const throw ();
00176 protected:
00177 boost::shared_ptr<xn::DepthMetaData> depth_md_;
00178 float baseline_;
00179 float focal_length_;
00180 XnUInt64 shadow_value_;
00181 XnUInt64 no_sample_value_;
00182 } ;
00183
00184 DepthImage::DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ()
00185 : depth_md_ (depth_meta_data)
00186 , baseline_ (baseline)
00187 , focal_length_ (focal_length)
00188 , shadow_value_ (shadow_value)
00189 , no_sample_value_ (no_sample_value) { }
00190
00191 DepthImage::~DepthImage () throw () { }
00192
00193 const xn::DepthMetaData&
00194 DepthImage::getDepthMetaData () const throw ()
00195 {
00196 return *depth_md_;
00197 }
00198
00199 float
00200 DepthImage::getBaseline () const throw ()
00201 {
00202 return baseline_;
00203 }
00204
00205 float
00206 DepthImage::getFocalLength () const throw ()
00207 {
00208 return focal_length_;
00209 }
00210
00211 XnUInt64
00212 DepthImage::getShadowValue () const throw ()
00213 {
00214 return shadow_value_;
00215 }
00216
00217 XnUInt64
00218 DepthImage::getNoSampleValue () const throw ()
00219 {
00220 return no_sample_value_;
00221 }
00222
00223 unsigned
00224 DepthImage::getWidth () const throw ()
00225 {
00226 return depth_md_->XRes ();
00227 }
00228
00229 unsigned
00230 DepthImage::getHeight () const throw ()
00231 {
00232 return depth_md_->YRes ();
00233 }
00234
00235 unsigned
00236 DepthImage::getFrameID () const throw ()
00237 {
00238 return depth_md_->FrameID ();
00239 }
00240
00241 unsigned long
00242 DepthImage::getTimeStamp () const throw ()
00243 {
00244 return static_cast<unsigned long> (depth_md_->Timestamp ());
00245 }
00246 }
00247 #endif
00248 #endif //__OPENNI_DEPTH_IMAGE