pcd_grabber.h
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) 2010-2012, Willow Garage, Inc.
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 
00038 #include <pcl/pcl_config.h>
00039 
00040 #ifndef PCL_IO_PCD_GRABBER_H_
00041 #define PCL_IO_PCD_GRABBER_H_
00042 
00043 #include <pcl/io/grabber.h>
00044 #include <pcl/common/time_trigger.h>
00045 #include <string>
00046 #include <vector>
00047 #include <pcl/ros/conversions.h>
00048 
00049 #ifdef HAVE_OPENNI
00050 #include <pcl/io/openni_camera/openni_depth_image.h>
00051 #endif
00052 
00053 namespace pcl
00054 {
00058   class PCL_EXPORTS PCDGrabberBase : public Grabber
00059   {
00060     public:
00066       PCDGrabberBase (const std::string& pcd_file, float frames_per_second, bool repeat);
00067 
00073       PCDGrabberBase (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat);
00074 
00078       PCDGrabberBase (const PCDGrabberBase &src) : impl_ ()
00079       {
00080         *this = src;
00081       }
00082 
00086       PCDGrabberBase&
00087       operator = (const PCDGrabberBase &src)
00088       {
00089         impl_ = src.impl_;
00090         return (*this);
00091       }
00092 
00094       virtual ~PCDGrabberBase () throw ();
00095 
00097       virtual void 
00098       start ();
00099       
00101       virtual void 
00102       stop ();
00103       
00105       virtual void 
00106       trigger ();
00107 
00111       virtual bool 
00112       isRunning () const;
00113       
00115       virtual std::string 
00116       getName () const;
00117       
00119       virtual void 
00120       rewind ();
00121 
00123       virtual float 
00124       getFramesPerSecond () const;
00125 
00127       bool 
00128       isRepeatOn () const;
00129 
00130     private:
00131       virtual void 
00132       publish (const sensor_msgs::PointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const = 0;
00133 
00134       // to separate and hide the implementation from interface: PIMPL
00135       struct PCDGrabberImpl;
00136       PCDGrabberImpl* impl_;
00137   };
00138 
00140   template <typename T> class PointCloud;
00141   template <typename PointT> class PCDGrabber : public PCDGrabberBase
00142   {
00143     public:
00144       PCDGrabber (const std::string& pcd_path, float frames_per_second = 0, bool repeat = false);
00145       PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second = 0, bool repeat = false);
00146     protected:
00147       virtual void 
00148       publish (const sensor_msgs::PointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const;
00149       
00150       boost::signals2::signal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>* signal_;
00151 
00152 #ifdef HAVE_OPENNI
00153       boost::signals2::signal<void (const boost::shared_ptr<openni_wrapper::DepthImage>&)>*     depth_image_signal_;
00154 #endif
00155   };
00156 
00158   template<typename PointT>
00159   PCDGrabber<PointT>::PCDGrabber (const std::string& pcd_path, float frames_per_second, bool repeat)
00160   : PCDGrabberBase (pcd_path, frames_per_second, repeat)
00161   {
00162     signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>();
00163 #ifdef HAVE_OPENNI
00164     depth_image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::DepthImage>&)> ();
00165 #endif
00166   }
00167 
00169   template<typename PointT>
00170   PCDGrabber<PointT>::PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat)
00171     : PCDGrabberBase (pcd_files, frames_per_second, repeat), signal_ ()
00172   {
00173     signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>();
00174 #ifdef HAVE_OPENNI
00175     depth_image_signal_ = createSignal <void (const boost::shared_ptr<openni_wrapper::DepthImage>&)> ();
00176 #endif
00177   }
00178 
00180   template<typename PointT> void 
00181   PCDGrabber<PointT>::publish (const sensor_msgs::PointCloud2& blob, const Eigen::Vector4f& origin, const Eigen::Quaternionf& orientation) const
00182   {
00183     typename pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT> ());
00184     pcl::fromROSMsg (blob, *cloud);
00185     cloud->sensor_origin_ = origin;
00186     cloud->sensor_orientation_ = orientation;
00187 
00188     signal_->operator () (cloud);
00189 
00190 #ifdef HAVE_OPENNI
00191     // If dataset is not organized, return
00192     if (!cloud->isOrganized ())
00193       return;
00194 
00195     boost::shared_ptr<xn::DepthMetaData> depth_meta_data (new xn::DepthMetaData);
00196     depth_meta_data->AllocateData (cloud->width, cloud->height);
00197     XnDepthPixel* depth_map = depth_meta_data->WritableData ();
00198     uint32_t k = 0;
00199     for (uint32_t i = 0; i < cloud->height; ++i)
00200       for (uint32_t j = 0; j < cloud->width; ++j)
00201       {
00202         depth_map[k] = static_cast<XnDepthPixel> ((*cloud)[k].z * 1000);
00203         ++k;
00204       }
00205 
00206     boost::shared_ptr<openni_wrapper::DepthImage> depth_image (new openni_wrapper::DepthImage (depth_meta_data, 0.075f, 525, 0, 0));
00207     if (depth_image_signal_->num_slots() > 0)
00208       depth_image_signal_->operator()(depth_image);
00209 #endif
00210   }
00211 }
00212 #endif


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