Point Cloud Library (PCL)
1.3.1
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 Willow Garage, Inc. 00005 * Suat Gedikli <gedikli@willowgarage.com> 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of Willow Garage, Inc. nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 */ 00037 #include <pcl/pcl_config.h> 00038 #ifdef HAVE_OPENNI 00039 00040 #ifndef __OPENNI_DEPTH_IMAGE__ 00041 #define __OPENNI_DEPTH_IMAGE__ 00042 00043 #include <XnCppWrapper.h> 00044 00045 #include <pcl/pcl_macros.h> 00046 #include "openni_exception.h" 00047 #include <boost/shared_ptr.hpp> 00048 00049 namespace openni_wrapper 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 00062 inline DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw (); 00063 inline virtual ~DepthImage () throw (); 00064 00065 inline const xn::DepthMetaData& getDepthMetaData () const throw (); 00066 void fillDisparityImage (unsigned width, unsigned height, float* disparity_buffer, unsigned line_step = 0) const; 00067 void fillDepthImage (unsigned width, unsigned height, float* depth_buffer, unsigned line_step = 0) const; 00068 void fillDepthImageRaw (unsigned width, unsigned height, unsigned short* depth_buffer, unsigned line_step = 0) const; 00069 00070 inline float getBaseline () const throw (); 00071 inline float getFocalLength () const throw (); 00072 inline XnUInt64 getShadowValue () const throw (); 00073 inline XnUInt64 getNoSampleValue () const throw (); 00074 inline unsigned getWidth () const throw (); 00075 inline unsigned getHeight () const throw (); 00076 inline unsigned getFrameID () const throw (); 00077 inline unsigned long getTimeStamp () const throw (); 00078 protected: 00079 boost::shared_ptr<xn::DepthMetaData> depth_md_; 00080 float baseline_; 00081 float focal_length_; 00082 XnUInt64 shadow_value_; 00083 XnUInt64 no_sample_value_; 00084 }; 00085 00086 DepthImage::DepthImage (boost::shared_ptr<xn::DepthMetaData> depth_meta_data, float baseline, float focal_length, XnUInt64 shadow_value, XnUInt64 no_sample_value) throw () 00087 : depth_md_ (depth_meta_data) 00088 , baseline_ (baseline) 00089 , focal_length_ (focal_length) 00090 , shadow_value_ (shadow_value) 00091 , no_sample_value_ (no_sample_value) 00092 { 00093 } 00094 00095 DepthImage::~DepthImage () throw () 00096 { 00097 } 00098 00099 const xn::DepthMetaData& DepthImage::getDepthMetaData () const throw () 00100 { 00101 return *depth_md_; 00102 } 00103 00104 float DepthImage::getBaseline () const throw () 00105 { 00106 return baseline_; 00107 } 00108 00109 float DepthImage::getFocalLength () const throw () 00110 { 00111 return focal_length_; 00112 } 00113 00114 XnUInt64 DepthImage::getShadowValue () const throw () 00115 { 00116 return shadow_value_; 00117 } 00118 00119 XnUInt64 DepthImage::getNoSampleValue () const throw () 00120 { 00121 return no_sample_value_; 00122 } 00123 00124 unsigned DepthImage::getWidth () const throw () 00125 { 00126 return depth_md_->XRes (); 00127 } 00128 00129 unsigned DepthImage::getHeight () const throw () 00130 { 00131 return depth_md_->YRes (); 00132 } 00133 00134 unsigned DepthImage::getFrameID () const throw () 00135 { 00136 return depth_md_->FrameID (); 00137 } 00138 00139 unsigned long DepthImage::getTimeStamp () const throw () 00140 { 00141 return (unsigned long) depth_md_->Timestamp (); 00142 } 00143 } // namespace 00144 #endif 00145 #endif //__OPENNI_DEPTH_IMAGE