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 #ifndef __OPENNI_DEPTH_IMAGE__
00038 #define __OPENNI_DEPTH_IMAGE__
00039
00040 #include <XnCppWrapper.h>
00041
00042 #include "openni_exception.h"
00043 #include <boost/shared_ptr.hpp>
00044
00045 namespace openni_wrapper
00046 {
00052 class DepthImage
00053 {
00054 public:
00055 typedef boost::shared_ptr<DepthImage> Ptr;
00056 typedef boost::shared_ptr<const DepthImage> ConstPtr;
00057
00058 inline DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ();
00059 inline virtual ~DepthImage () throw ();
00060
00061 inline const xn::DepthMetaData& getDepthMetaData () const throw ();
00062 void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const throw (OpenNIException);
00063 void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const throw (OpenNIException);
00064 void fillDepthImageRaw (unsigned width, unsigned height, short* depth_buffer, unsigned line_step = 0) const throw (OpenNIException);
00065
00066 inline float getBaseline () const throw ();
00067 inline float getFocalLength () const throw ();
00068 inline XnUInt64 getShadowValue () const throw ();
00069 inline XnUInt64 getNoSampleValue () const throw ();
00070 inline unsigned getWidth () const throw ();
00071 inline unsigned getHeight () const throw ();
00072 inline unsigned getFrameID () const throw ();
00073 inline unsigned long getTimeStamp () const throw ();
00074 protected:
00075 boost::shared_ptr<xn::DepthMetaData> depth_md_;
00076 float baseline_;
00077 float focal_length_;
00078 XnUInt64 shadow_value_;
00079 XnUInt64 no_sample_value_;
00080 };
00081
00082 DepthImage::DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw ()
00083 : depth_md_ (depth_meta_data)
00084 , baseline_ (baseline)
00085 , focal_length_ (focal_length)
00086 , shadow_value_ (shadow_value)
00087 , no_sample_value_ (no_sample_value)
00088 {
00089 }
00090
00091 DepthImage::~DepthImage () throw ()
00092 {
00093 }
00094
00095 const xn::DepthMetaData& DepthImage::getDepthMetaData () const throw ()
00096 {
00097 return *depth_md_;
00098 }
00099
00100 float DepthImage::getBaseline () const throw ()
00101 {
00102 return baseline_;
00103 }
00104
00105 float DepthImage::getFocalLength () const throw ()
00106 {
00107 return focal_length_;
00108 }
00109
00110 XnUInt64 DepthImage::getShadowValue () const throw ()
00111 {
00112 return shadow_value_;
00113 }
00114
00115 XnUInt64 DepthImage::getNoSampleValue () const throw ()
00116 {
00117 return no_sample_value_;
00118 }
00119
00120 unsigned DepthImage::getWidth () const throw ()
00121 {
00122 return depth_md_->XRes ();
00123 }
00124
00125 unsigned DepthImage::getHeight () const throw ()
00126 {
00127 return depth_md_->YRes ();
00128 }
00129
00130 unsigned DepthImage::getFrameID () const throw ()
00131 {
00132 return depth_md_->FrameID ();
00133 }
00134
00135 unsigned long DepthImage::getTimeStamp () const throw ()
00136 {
00137 return depth_md_->Timestamp ();
00138 }
00139 }
00140 #endif //__OPENNI_DEPTH_IMAGE