$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011 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 <openni_camera/openni_image_yuv_422.h> 00038 #include <sstream> 00039 #include <iostream> 00040 00041 #define CLIP_CHAR(c) ((c)>255?255:(c)<0?0:(c)) 00042 00043 using namespace std; 00044 namespace openni_wrapper 00045 { 00046 00047 ImageYUV422::ImageYUV422 (boost::shared_ptr<xn::ImageMetaData> image_meta_data) throw () 00048 : Image (image_meta_data) 00049 { 00050 } 00051 00052 ImageYUV422::~ImageYUV422 () throw () 00053 { 00054 } 00055 00056 bool ImageYUV422::isResizingSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const 00057 { 00058 return ImageYUV422::resizingSupported (input_width, input_height, output_width, output_height); 00059 } 00060 00061 void ImageYUV422::fillRGB (unsigned width, unsigned height, unsigned char* rgb_buffer, unsigned rgb_line_step) const throw (OpenNIException) 00062 { 00063 // 0 1 2 3 00064 // u y1 v y2 00065 00066 if (image_md_->XRes() != width && image_md_->YRes() != height) 00067 { 00068 if (width > image_md_->XRes () || height > image_md_->YRes ()) 00069 THROW_OPENNI_EXCEPTION ("Upsampling not supported. Request was: %d x %d -> %d x %d", image_md_->XRes (), image_md_->YRes (), width, height); 00070 00071 if ( image_md_->XRes () % width != 0 || image_md_->YRes () % height != 0 00072 || (image_md_->XRes () / width) & 0x01 || (image_md_->YRes () / height & 0x01) ) 00073 THROW_OPENNI_EXCEPTION ("Downsampling only possible for power of two scale in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); 00074 } 00075 00076 register const XnUInt8* yuv_buffer = image_md_->Data(); 00077 00078 unsigned rgb_line_skip = 0; 00079 if (rgb_line_step != 0) 00080 rgb_line_skip = rgb_line_step - width * 3; 00081 00082 if (image_md_->XRes() == width && image_md_->YRes() == height) 00083 { 00084 for( register unsigned yIdx = 0; yIdx < height; ++yIdx, rgb_buffer += rgb_line_skip ) 00085 { 00086 for( register unsigned xIdx = 0; xIdx < width; xIdx += 2, rgb_buffer += 6, yuv_buffer += 4 ) 00087 { 00088 int v = yuv_buffer[2] - 128; 00089 int u = yuv_buffer[0] - 128; 00090 00091 rgb_buffer[0] = CLIP_CHAR (yuv_buffer[1] + ((v * 18678 + 8192 ) >> 14)); 00092 rgb_buffer[1] = CLIP_CHAR (yuv_buffer[1] + ((v * -9519 - u * 6472 + 8192 ) >> 14)); 00093 rgb_buffer[2] = CLIP_CHAR (yuv_buffer[1] + ((u * 33292 + 8192 ) >> 14)); 00094 00095 rgb_buffer[3] = CLIP_CHAR (yuv_buffer[3] + ((v * 18678 + 8192 ) >> 14)); 00096 rgb_buffer[4] = CLIP_CHAR (yuv_buffer[3] + ((v * -9519 - u * 6472 + 8192 ) >> 14)); 00097 rgb_buffer[5] = CLIP_CHAR (yuv_buffer[3] + ((u * 33292 + 8192 ) >> 14)); 00098 } 00099 } 00100 } 00101 else 00102 { 00103 register unsigned yuv_step = image_md_->XRes() / width; 00104 register unsigned yuv_x_step = yuv_step << 1; 00105 register unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); 00106 00107 for( register unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, rgb_buffer += rgb_line_skip ) 00108 { 00109 for( register unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, rgb_buffer += 3, yuv_buffer += yuv_x_step ) 00110 { 00111 int v = yuv_buffer[2] - 128; 00112 int u = yuv_buffer[0] - 128; 00113 00114 rgb_buffer[0] = CLIP_CHAR (yuv_buffer[1] + ((v * 18678 + 8192 ) >> 14)); 00115 rgb_buffer[1] = CLIP_CHAR (yuv_buffer[1] + ((v * -9519 - u * 6472 + 8192 ) >> 14)); 00116 rgb_buffer[2] = CLIP_CHAR (yuv_buffer[1] + ((u * 33292 + 8192 ) >> 14)); 00117 } 00118 } 00119 } 00120 } 00121 00122 void ImageYUV422::fillGrayscale (unsigned width, unsigned height, unsigned char* gray_buffer, unsigned gray_line_step) const throw (OpenNIException) 00123 { 00124 // u y1 v y2 00125 if (width > image_md_->XRes () || height > image_md_->YRes ()) 00126 THROW_OPENNI_EXCEPTION ("Upsampling not supported. Request was: %d x %d -> %d x %d", image_md_->XRes (), image_md_->YRes (), width, height); 00127 00128 if (image_md_->XRes () % width != 0 || image_md_->YRes () % height != 0) 00129 THROW_OPENNI_EXCEPTION ("Downsampling only possible for integer scales in both dimensions. Request was %d x %d -> %d x %d.", image_md_->XRes (), image_md_->YRes (), width, height); 00130 00131 unsigned gray_line_skip = 0; 00132 if (gray_line_step != 0) 00133 gray_line_skip = gray_line_step - width; 00134 00135 register unsigned yuv_step = image_md_->XRes() / width; 00136 register unsigned yuv_x_step = yuv_step << 1; 00137 register unsigned yuv_skip = (image_md_->YRes() / height - 1) * ( image_md_->XRes() << 1 ); 00138 register const XnUInt8* yuv_buffer = (image_md_->Data() + 1); 00139 00140 for( register unsigned yIdx = 0; yIdx < image_md_->YRes(); yIdx += yuv_step, yuv_buffer += yuv_skip, gray_buffer += gray_line_skip ) 00141 { 00142 for( register unsigned xIdx = 0; xIdx < image_md_->XRes(); xIdx += yuv_step, ++gray_buffer, yuv_buffer += yuv_x_step ) 00143 { 00144 *gray_buffer = *yuv_buffer; 00145 } 00146 } 00147 } 00148 } //namespace