openni_device_oni.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  */
00038 #include <pcl/pcl_config.h>
00039 #ifdef HAVE_OPENNI
00040 
00041 #ifdef __GNUC__
00042 #pragma GCC diagnostic ignored "-Wold-style-cast"
00043 #endif
00044 
00045 #include <pcl/io/openni_camera/openni_device_oni.h>
00046 #include <pcl/io/openni_camera/openni_image_rgb24.h>
00047 
00049 openni_wrapper::DeviceONI::DeviceONI (
00050     xn::Context& context, 
00051     const std::string& file_name, 
00052     bool repeat, 
00053     bool streaming)
00054   : OpenNIDevice (context)
00055   , streaming_  (streaming)
00056   , depth_stream_running_ (false)
00057   , image_stream_running_ (false)
00058   , ir_stream_running_ (false)
00059 {
00060   XnStatus status;
00061 #if (XN_MINOR_VERSION >= 3)
00062   status = context_.OpenFileRecording (file_name.c_str(), player_);
00063   if (status != XN_STATUS_OK)
00064     THROW_OPENNI_EXCEPTION ("Could not open ONI file. Reason: %s", xnGetStatusString (status));
00065 #else
00066   status = context_.OpenFileRecording (file_name.c_str());
00067   if (status != XN_STATUS_OK)
00068     THROW_OPENNI_EXCEPTION ("Could not open ONI file. Reason: %s", xnGetStatusString (status));
00069 
00070   status = context_.FindExistingNode (XN_NODE_TYPE_PLAYER, player_);
00071   if (status != XN_STATUS_OK)
00072     THROW_OPENNI_EXCEPTION ("Failed to find player node: %s\n", xnGetStatusString (status));
00073 #endif
00074 
00075   status = context_.FindExistingNode (XN_NODE_TYPE_DEPTH, depth_generator_);
00076   if (status != XN_STATUS_OK)
00077     THROW_OPENNI_EXCEPTION ("could not find depth stream in file %s. Reason: %s", file_name.c_str(), xnGetStatusString (status));
00078   else
00079   {
00080     available_depth_modes_.push_back (getDepthOutputMode ());
00081     depth_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIDepthDataAvailable), this, depth_callback_handle_);
00082   }
00083 
00084   status = context_.FindExistingNode (XN_NODE_TYPE_IMAGE, image_generator_);
00085   if (status == XN_STATUS_OK)
00086   {
00087     available_image_modes_.push_back (getImageOutputMode ());
00088     image_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIImageDataAvailable), this, image_callback_handle_);
00089   }
00090 
00091   status = context_.FindExistingNode(XN_NODE_TYPE_IR, ir_generator_);
00092   if (status == XN_STATUS_OK)
00093     ir_generator_.RegisterToNewDataAvailable (static_cast<xn::StateChangedHandler> (NewONIIRDataAvailable), this, ir_callback_handle_);
00094 
00095   device_node_info_ = player_.GetInfo ();
00096   Init ();
00097 
00098   player_.SetRepeat (repeat);
00099   if (streaming_)
00100     player_thread_ = boost::thread (&DeviceONI::PlayerThreadFunction, this);
00101 }
00102 
00104 openni_wrapper::DeviceONI::~DeviceONI() throw ()
00105 {
00106   if (streaming_)
00107   {
00108     quit_ = true;
00109     player_thread_.join();
00110   }
00111 }
00112 
00114 void 
00115 openni_wrapper::DeviceONI::startImageStream ()
00116 {
00117   if (hasImageStream() && !image_stream_running_)
00118     image_stream_running_ = true;
00119 }
00120 
00122 void 
00123 openni_wrapper::DeviceONI::stopImageStream ()
00124 {
00125   if (hasImageStream() && image_stream_running_)
00126     image_stream_running_ = false;
00127 }
00128 
00130 void 
00131 openni_wrapper::DeviceONI::startDepthStream ()
00132 {
00133   if (hasDepthStream() && !depth_stream_running_)
00134     depth_stream_running_ = true;
00135 }
00136 
00138 void 
00139 openni_wrapper::DeviceONI::stopDepthStream ()
00140 {
00141   if (hasDepthStream() && depth_stream_running_)
00142     depth_stream_running_ = false;
00143 }
00144 
00146 void 
00147 openni_wrapper::DeviceONI::startIRStream ()
00148 {
00149   if (hasIRStream() && !ir_stream_running_)
00150     ir_stream_running_ = true;
00151 }
00152 
00154 void 
00155 openni_wrapper::DeviceONI::stopIRStream ()
00156 {
00157   if (hasIRStream() && ir_stream_running_)
00158     ir_stream_running_ = false;
00159 }
00160 
00162 bool 
00163 openni_wrapper::DeviceONI::isImageStreamRunning () const throw ()
00164 {
00165  return (image_stream_running_);
00166 }
00167 
00169 bool 
00170 openni_wrapper::DeviceONI::isDepthStreamRunning () const throw ()
00171 {
00172   return (depth_stream_running_);
00173 }
00174 
00176 bool 
00177 openni_wrapper::DeviceONI::isIRStreamRunning () const throw ()
00178 {
00179   return (ir_stream_running_);
00180 }
00181 
00183 bool 
00184 openni_wrapper::DeviceONI::trigger (int relative_offset)
00185 {
00186   if (streaming_)
00187     THROW_OPENNI_EXCEPTION ("Virtual device is in streaming mode. Trigger not available.");
00188 
00189   if (relative_offset < 0)
00190   {
00191     XnStatus res = player_.SeekToFrame (depth_generator_.GetName (), relative_offset, XN_PLAYER_SEEK_CUR);
00192     if (res != XN_STATUS_OK) 
00193       return (false); 
00194   }
00195   else
00196   {
00197     if (player_.IsEOF ())
00198       return (false);
00199   }
00200 
00201   player_.ReadNext ();
00202   return (true);
00203 }
00204 
00206 bool 
00207 openni_wrapper::DeviceONI::isStreaming () const throw ()
00208 {
00209   return (streaming_);
00210 }
00211 
00213 void 
00214 openni_wrapper::DeviceONI::PlayerThreadFunction ()
00215 {
00216   quit_ = false;
00217   while (!quit_)
00218     player_.ReadNext ();
00219 }
00220 
00222 void __stdcall 
00223 openni_wrapper::DeviceONI::NewONIDepthDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00224 {
00225   DeviceONI* device = reinterpret_cast<DeviceONI*>(cookie);
00226   if (device->depth_stream_running_)
00227     device->depth_condition_.notify_all ();
00228 }
00229 
00231 void __stdcall 
00232 openni_wrapper::DeviceONI::NewONIImageDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00233 {
00234   DeviceONI* device = reinterpret_cast<DeviceONI*> (cookie);
00235   if (device->image_stream_running_)
00236     device->image_condition_.notify_all ();
00237 }
00238 
00240 void __stdcall 
00241 openni_wrapper::DeviceONI::NewONIIRDataAvailable (xn::ProductionNode&, void* cookie) throw ()
00242 {
00243   DeviceONI* device = reinterpret_cast<DeviceONI*> (cookie);
00244   if (device->ir_stream_running_)
00245     device->ir_condition_.notify_all ();
00246 }
00247 
00249 boost::shared_ptr<openni_wrapper::Image> 
00250 openni_wrapper::DeviceONI::getCurrentImage(boost::shared_ptr<xn::ImageMetaData> image_meta_data) const throw ()
00251 {
00252   return (boost::shared_ptr<openni_wrapper::Image> (new openni_wrapper::ImageRGB24 (image_meta_data)));
00253 }
00254 
00256 bool 
00257 openni_wrapper::DeviceONI::isImageResizeSupported(unsigned input_width, unsigned input_height, unsigned output_width, unsigned output_height) const throw ()
00258 {
00259   return (openni_wrapper::ImageRGB24::resizingSupported (input_width, input_height, output_width, output_height));
00260 }
00261 
00262 #endif //HAVE_OPENNI
00263 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:26:23