|
Point Cloud Library (PCL)
1.4.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 Willow Garage, Inc. 00005 * 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of Willow Garage, Inc. nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 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 #include <pcl/pcl_macros.h> 00045 #include "openni_exception.h" 00046 #include <boost/shared_ptr.hpp> 00047 00048 namespace openni_wrapper 00049 { 00050 00056 class PCL_EXPORTS DepthImage 00057 { 00058 public: 00059 typedef boost::shared_ptr<DepthImage> Ptr; 00060 typedef boost::shared_ptr<const DepthImage> ConstPtr; 00061 00073 inline DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw (); 00074 00079 inline virtual ~DepthImage () throw (); 00080 00086 inline const xn::DepthMetaData& getDepthMetaData () const throw (); 00087 00097 void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const; 00098 00108 void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const; 00109 00119 void fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const; 00120 00126 inline float getBaseline () const throw (); 00127 00133 inline float getFocalLength () const throw (); 00134 00140 inline XnUInt64 getShadowValue () const throw (); 00141 00147 inline XnUInt64 getNoSampleValue () const throw (); 00148 00153 inline unsigned getWidth () const throw (); 00154 00159 inline unsigned getHeight () const throw (); 00160 00166 inline unsigned getFrameID () const throw (); 00167 00174 inline unsigned long getTimeStamp () const throw (); 00175 protected: 00176 boost::shared_ptr<xn::DepthMetaData> depth_md_; 00177 float baseline_; 00178 float focal_length_; 00179 XnUInt64 shadow_value_; 00180 XnUInt64 no_sample_value_; 00181 } ; 00182 00183 DepthImage::DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw () 00184 : depth_md_ (depth_meta_data) 00185 , baseline_ (baseline) 00186 , focal_length_ (focal_length) 00187 , shadow_value_ (shadow_value) 00188 , no_sample_value_ (no_sample_value) { } 00189 00190 DepthImage::~DepthImage () throw () { } 00191 00192 const xn::DepthMetaData& 00193 DepthImage::getDepthMetaData () const throw () 00194 { 00195 return *depth_md_; 00196 } 00197 00198 float 00199 DepthImage::getBaseline () const throw () 00200 { 00201 return baseline_; 00202 } 00203 00204 float 00205 DepthImage::getFocalLength () const throw () 00206 { 00207 return focal_length_; 00208 } 00209 00210 XnUInt64 00211 DepthImage::getShadowValue () const throw () 00212 { 00213 return shadow_value_; 00214 } 00215 00216 XnUInt64 00217 DepthImage::getNoSampleValue () const throw () 00218 { 00219 return no_sample_value_; 00220 } 00221 00222 unsigned 00223 DepthImage::getWidth () const throw () 00224 { 00225 return depth_md_->XRes (); 00226 } 00227 00228 unsigned 00229 DepthImage::getHeight () const throw () 00230 { 00231 return depth_md_->YRes (); 00232 } 00233 00234 unsigned 00235 DepthImage::getFrameID () const throw () 00236 { 00237 return depth_md_->FrameID (); 00238 } 00239 00240 unsigned long 00241 DepthImage::getTimeStamp () const throw () 00242 { 00243 return (unsigned long) depth_md_->Timestamp (); 00244 } 00245 } // namespace 00246 #endif 00247 #endif //__OPENNI_DEPTH_IMAGE
1.7.6.1