openni_device_oni.cpp
Go to the documentation of this file.
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 <pcl/pcl_config.h>
00038 #ifdef HAVE_OPENNI
00039 
00040 #include <pcl/io/openni_camera/openni_device_oni.h>
00041 #include <pcl/io/openni_camera/openni_image_rgb24.h>
00042 
00043 using namespace std;
00044 using namespace boost;
00045 
00046 namespace openni_wrapper
00047 {
00048 
00049 DeviceONI::DeviceONI(xn::Context& context, const std::string& file_name, bool repeat, bool streaming)
00050   : OpenNIDevice(context)
00051   , streaming_ (streaming)
00052   , depth_stream_running_ (false)
00053   , image_stream_running_ (false)
00054   , ir_stream_running_ (false)
00055 {
00056   XnStatus status;
00057 #if (XN_MINOR_VERSION >= 3)
00058   status = context_.OpenFileRecording(file_name.c_str(), player_);
00059   if (status != XN_STATUS_OK)
00060     THROW_OPENNI_EXCEPTION("Could not open ONI file. Reason: %s", xnGetStatusString(status));
00061 #else
00062   status = context_.OpenFileRecording(file_name.c_str());
00063   if (status != XN_STATUS_OK)
00064     THROW_OPENNI_EXCEPTION("Could not open ONI file. Reason: %s", xnGetStatusString(status));
00065 
00066   status = context.FindExistingNode(XN_NODE_TYPE_PLAYER, player_);
00067   if (status != XN_STATUS_OK)
00068     THROW_OPENNI_EXCEPTION("Failed to find player node: %s\n", xnGetStatusString(status));
00069 #endif
00070 
00071   status = context.FindExistingNode(XN_NODE_TYPE_DEPTH, depth_generator_);
00072   if (status != XN_STATUS_OK)
00073     THROW_OPENNI_EXCEPTION("could not find depth stream in file %s. Reason: %s", file_name.c_str(), xnGetStatusString(status));
00074   else
00075   {
00076     available_depth_modes_.push_back(getDepthOutputMode());
00077     depth_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIDepthDataAvailable), this, depth_callback_handle_);
00078   }
00079 
00080   status = context.FindExistingNode(XN_NODE_TYPE_IMAGE, image_generator_);
00081   if (status == XN_STATUS_OK)
00082   {
00083     available_image_modes_.push_back(getImageOutputMode());
00084     image_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIImageDataAvailable), this, image_callback_handle_);
00085   }
00086 
00087   status = context.FindExistingNode(XN_NODE_TYPE_IR, ir_generator_);
00088   if (status == XN_STATUS_OK)
00089     ir_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIIRDataAvailable), this, ir_callback_handle_);
00090 
00091   device_node_info_ = player_.GetInfo();
00092 
00093   Init ();
00094 
00095   player_.SetRepeat(repeat);
00096   if (streaming_)
00097     player_thread_ = boost::thread (&DeviceONI::PlayerThreadFunction, this);
00098 }
00099 
00100 DeviceONI::~DeviceONI() throw ()
00101 {
00102   if (streaming_)
00103   {
00104     quit_ = true;
00105     player_thread_.join();
00106   }
00107 }
00108 
00109 void DeviceONI::startImageStream ()
00110 {
00111   if (hasImageStream() && !image_stream_running_)
00112     image_stream_running_ = true;
00113 }
00114 
00115 void DeviceONI::stopImageStream ()
00116 {
00117   if (hasImageStream() && image_stream_running_)
00118     image_stream_running_ = false;
00119 }
00120 
00121 void DeviceONI::startDepthStream ()
00122 {
00123   if (hasDepthStream() && !depth_stream_running_)
00124     depth_stream_running_ = true;
00125 }
00126 
00127 void DeviceONI::stopDepthStream ()
00128 {
00129   if (hasDepthStream() && depth_stream_running_)
00130     depth_stream_running_ = false;
00131 }
00132 
00133 void DeviceONI::startIRStream ()
00134 {
00135   if (hasIRStream() && !ir_stream_running_)
00136     ir_stream_running_ = true;
00137 }
00138 
00139 void DeviceONI::stopIRStream ()
00140 {
00141   if (hasIRStream() && ir_stream_running_)
00142     ir_stream_running_ = false;
00143 }
00144 
00145 bool DeviceONI::isImageStreamRunning () const throw ()
00146 {
00147  return image_stream_running_;
00148 }
00149 
00150 bool DeviceONI::isDepthStreamRunning () const throw ()
00151 {
00152   return depth_stream_running_;
00153 }
00154 
00155 bool DeviceONI::isIRStreamRunning () const throw ()
00156 {
00157   return ir_stream_running_;
00158 }
00159 
00160 bool DeviceONI::trigger ()
00161 {
00162   if (player_.IsEOF())
00163     return false;
00164 
00165   if (streaming_)
00166     THROW_OPENNI_EXCEPTION ("Virtual device is in streaming mode. Trigger not available.");
00167 
00168   player_.ReadNext();
00169   return true;
00170 }
00171 
00172 bool DeviceONI::isStreaming () const throw ()
00173 {
00174   return streaming_;
00175 }
00176 
00177 void DeviceONI::PlayerThreadFunction()
00178 {
00179   quit_ = false;
00180   while (!quit_)
00181     player_.ReadNext();
00182 }
00183 
00184 void __stdcall DeviceONI::NewONIDepthDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00185 {
00186   DeviceONI* device = reinterpret_cast<DeviceONI*>(cookie);
00187   if (device->depth_stream_running_)
00188     device->depth_condition_.notify_all ();
00189 }
00190 
00191 void __stdcall DeviceONI::NewONIImageDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00192 {
00193   DeviceONI* device = reinterpret_cast<DeviceONI*>(cookie);
00194   if (device->image_stream_running_)
00195     device->image_condition_.notify_all ();
00196 }
00197 
00198 void __stdcall DeviceONI::NewONIIRDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00199 {
00200   DeviceONI* device = reinterpret_cast<DeviceONI*>(cookie);
00201   if (device->ir_stream_running_)
00202     device->ir_condition_.notify_all ();
00203 }
00204 
00205 boost::shared_ptr<Image> DeviceONI::getCurrentImage(boost::shared_ptr<xn::ImageMetaData> image_meta_data) const throw ()
00206 {
00207   return boost::shared_ptr<Image > (new ImageRGB24(image_meta_data));
00208 }
00209 
00210 bool DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw ()
00211 {
00212   return ImageRGB24::resizingSupported (input_width, input_height, output_width, output_height);
00213 }
00214 
00215 }
00216 
00217 #endif //HAVE_OPENNI
00218 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:16:00