$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_xtion.h> 00038 #include <iostream> 00039 #include <sstream> 00040 #include <boost/thread/mutex.hpp> 00041 00042 using namespace std; 00043 using namespace boost; 00044 00045 namespace openni_wrapper 00046 { 00047 00048 DeviceXtionPro::DeviceXtionPro (xn::Context& context, const xn::NodeInfo& device_node, const xn::NodeInfo& depth_node, const xn::NodeInfo& ir_node) throw (OpenNIException) 00049 : OpenNIDevice (context, device_node, depth_node, ir_node) 00050 { 00051 // setup stream modes 00052 enumAvailableModes (); 00053 setDepthOutputMode (getDefaultDepthMode ()); 00054 setIROutputMode (getDefaultIRMode ()); 00055 00056 lock_guard<mutex> depth_lock(depth_mutex_); 00057 XnStatus status = depth_generator_.SetIntProperty ("RegistrationType", 1); 00058 if (status != XN_STATUS_OK) 00059 THROW_OPENNI_EXCEPTION ("Error setting the registration type. Reason: %s", xnGetStatusString (status)); 00060 } 00061 00062 DeviceXtionPro::~DeviceXtionPro () throw () 00063 { 00064 depth_mutex_.lock (); 00065 depth_generator_.UnregisterFromNewDataAvailable (depth_callback_handle_); 00066 depth_mutex_.unlock (); 00067 } 00068 00069 bool DeviceXtionPro::isImageResizeSupported (unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw () 00070 { 00071 return false; 00072 } 00073 00074 void DeviceXtionPro::enumAvailableModes () throw (OpenNIException) 00075 { 00076 XnMapOutputMode output_mode; 00077 available_image_modes_.clear(); 00078 available_depth_modes_.clear(); 00079 00080 // Depth Modes 00081 output_mode.nFPS = 30; 00082 output_mode.nXRes = XN_VGA_X_RES; 00083 output_mode.nYRes = XN_VGA_Y_RES; 00084 available_depth_modes_.push_back (output_mode); 00085 00086 output_mode.nFPS = 25; 00087 output_mode.nXRes = XN_VGA_X_RES; 00088 output_mode.nYRes = XN_VGA_Y_RES; 00089 available_depth_modes_.push_back (output_mode); 00090 00091 output_mode.nFPS = 25; 00092 output_mode.nXRes = XN_QVGA_X_RES; 00093 output_mode.nYRes = XN_QVGA_Y_RES; 00094 available_depth_modes_.push_back (output_mode); 00095 00096 output_mode.nFPS = 30; 00097 output_mode.nXRes = XN_QVGA_X_RES; 00098 output_mode.nYRes = XN_QVGA_Y_RES; 00099 available_depth_modes_.push_back (output_mode); 00100 00101 output_mode.nFPS = 60; 00102 output_mode.nXRes = XN_QVGA_X_RES; 00103 output_mode.nYRes = XN_QVGA_Y_RES; 00104 available_depth_modes_.push_back (output_mode); 00105 } 00106 00107 boost::shared_ptr<Image> DeviceXtionPro::getCurrentImage (boost::shared_ptr<xn::ImageMetaData> image_data) const throw () 00108 { 00109 return boost::shared_ptr<Image> ((Image*)0); 00110 } 00111 00112 void DeviceXtionPro::startDepthStream () throw (OpenNIException) 00113 { 00114 if (isDepthRegistered ()) 00115 { 00116 // Reset the view point 00117 setDepthRegistration (false); 00118 00119 // Start the stream 00120 OpenNIDevice::startDepthStream (); 00121 00122 // Register the stream 00123 setDepthRegistration (true); 00124 } 00125 else 00126 // Start the stream 00127 OpenNIDevice::startDepthStream (); 00128 } 00129 00130 } //namespace