$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_device_kinect.h> 00038 #include <openni_camera/openni_image_bayer_grbg.h> 00039 #include <iostream> 00040 #include <sstream> 00041 #include <boost/thread/mutex.hpp> 00042 00043 using namespace std; 00044 using namespace boost; 00045 00046 namespace openni_wrapper 00047 { 00048 00049 DeviceKinect::DeviceKinect (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& image_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) 00050 : OpenNIDevice (context, device_node, image_node, depth_node, ir_node) 00051 , debayering_method_ (ImageBayerGRBG::EdgeAwareWeighted) 00052 { 00053 // setup stream modes 00054 enumAvailableModes (); 00055 setDepthOutputMode (getDefaultDepthMode ()); 00056 setImageOutputMode (getDefaultImageMode ()); 00057 setIROutputMode (getDefaultIRMode ()); 00058 00059 // device specific initialization 00060 XnStatus status; 00061 00062 unique_lock<mutex> image_lock(image_mutex_); 00063 // set kinect specific format. Thus input = uncompressed Bayer, output = grayscale = bypass = bayer 00064 status = image_generator_.SetIntProperty ("InputFormat", 6); 00065 if (status != XN_STATUS_OK) 00066 THROW_OPENNI_EXCEPTION ("Error setting the image input format to Uncompressed 8-bit BAYER. Reason: %s", xnGetStatusString (status)); 00067 00068 // Grayscale: bypass debayering -> gives us bayer pattern! 00069 status = image_generator_.SetPixelFormat (XN_PIXEL_FORMAT_GRAYSCALE_8_BIT); 00070 if (status != XN_STATUS_OK) 00071 THROW_OPENNI_EXCEPTION ("Failed to set image pixel format to 8bit-grayscale. Reason: %s", xnGetStatusString (status)); 00072 image_lock.unlock (); 00073 00074 lock_guard<mutex> depth_lock(depth_mutex_); 00075 // RegistrationType should be 2 (software) for Kinect, 1 (hardware) for PS 00076 status = depth_generator_.SetIntProperty ("RegistrationType", 2); 00077 if (status != XN_STATUS_OK) 00078 THROW_OPENNI_EXCEPTION ("Error setting the registration type. Reason: %s", xnGetStatusString (status)); 00079 } 00080 00081 DeviceKinect::~DeviceKinect () throw () 00082 { 00083 depth_mutex_.lock (); 00084 depth_generator_.UnregisterFromNewDataAvailable (depth_callback_handle_); 00085 depth_mutex_.unlock (); 00086 00087 image_mutex_.lock (); 00088 image_generator_.UnregisterFromNewDataAvailable (image_callback_handle_); 00089 image_mutex_.unlock (); 00090 } 00091 00092 bool DeviceKinect::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () 00093 { 00094 return ImageBayerGRBG::resizingSupported (input_width, input_height, output_width, output_height); 00095 } 00096 00097 void DeviceKinect::enumAvailableModes () throw (OpenNIException) 00098 { 00099 XnMapOutputMode output_mode; 00100 available_image_modes_.clear(); 00101 available_depth_modes_.clear(); 00102 00103 output_mode.nFPS = 30; 00104 output_mode.nXRes = XN_VGA_X_RES; 00105 output_mode.nYRes = XN_VGA_Y_RES; 00106 available_image_modes_.push_back (output_mode); 00107 available_depth_modes_.push_back (output_mode); 00108 00109 output_mode.nFPS = 15; 00110 output_mode.nXRes = XN_SXGA_X_RES; 00111 output_mode.nYRes = XN_SXGA_Y_RES; 00112 available_image_modes_.push_back (output_mode); 00113 } 00114 00115 boost::shared_ptr<Image> DeviceKinect::getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () 00116 { 00117 return boost::shared_ptr<Image> (new ImageBayerGRBG (image_data, debayering_method_)); 00118 } 00119 00120 void DeviceKinect::setSynchronization (bool on_off) throw (OpenNIException) 00121 { 00122 if (on_off) 00123 THROW_OPENNI_EXCEPTION ("Microsoft Kinect does not support Hardware synchronization."); 00124 } 00125 00126 bool DeviceKinect::isSynchronized () const throw (OpenNIException) 00127 { 00128 return false; 00129 } 00130 00131 bool DeviceKinect::isSynchronizationSupported () const throw () 00132 { 00133 return false; 00134 } 00135 00136 bool DeviceKinect::isDepthCropped () const throw (OpenNIException) 00137 { 00138 return false; 00139 } 00140 00141 void DeviceKinect::setDepthCropping (unsigned x, unsigned y, unsigned width, unsigned height) throw (OpenNIException) 00142 { 00143 if (width != 0 && height != 0) 00144 THROW_OPENNI_EXCEPTION ("Microsoft Kinect does not support cropping for the depth stream."); 00145 } 00146 00147 bool DeviceKinect::isDepthCroppingSupported () const throw () 00148 { 00149 return false; 00150 } 00151 00152 } //namespace