Point Cloud Library (PCL)
1.3.1
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * Author: Suat Gedikli (gedikli@willowgarage.com) 00035 */ 00036 00037 #include "pcl/pcl_config.h" 00038 #ifdef HAVE_OPENNI 00039 00040 #ifndef __PCL_IO_PCD_GRABBER__ 00041 #define __PCL_IO_PCD_GRABBER__ 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 namespace pcl 00050 { 00055 class PCL_EXPORTS PCDGrabberBase : public Grabber 00056 { 00057 public: 00064 PCDGrabberBase (const std::string& pcd_file, float frames_per_second, bool repeat); 00071 PCDGrabberBase (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat); 00075 virtual ~PCDGrabberBase () throw (); 00079 virtual void start (); 00083 virtual void stop (); 00088 virtual bool isRunning () const; 00093 virtual std::string getName () const; 00097 virtual void rewind (); 00098 private: 00099 virtual void publish (const sensor_msgs::PointCloud2& blob) const = 0; 00100 00101 // to seperate and hide the implementation from interface: PIMPL 00102 struct PCDGrabberImpl; 00103 PCDGrabberImpl* impl_; 00104 }; 00105 00109 template <typename T> class PointCloud; 00110 //class sensor_msgs::PointCloud2; 00111 template <typename PointT> class PCDGrabber : public PCDGrabberBase 00112 { 00113 public: 00114 PCDGrabber (const std::string& pcd_path, float frames_per_second = 0, bool repeat = false); 00115 PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second = 0, bool repeat = false); 00116 protected: 00117 virtual void publish (const sensor_msgs::PointCloud2& blob) const; 00118 boost::signals2::signal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>* signal_; 00119 }; 00120 00121 template<typename PointT> 00122 PCDGrabber<PointT>::PCDGrabber (const std::string& pcd_path, float frames_per_second, bool repeat) 00123 : PCDGrabberBase ( pcd_path, frames_per_second, repeat) 00124 { 00125 signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>(); 00126 } 00127 00128 template<typename PointT> 00129 PCDGrabber<PointT>::PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat) 00130 : PCDGrabberBase ( pcd_files, frames_per_second, repeat) 00131 { 00132 signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>(); 00133 } 00134 00135 template<typename PointT> 00136 void PCDGrabber<PointT>::publish (const sensor_msgs::PointCloud2& blob) const 00137 { 00138 typename pcl::PointCloud<PointT>::Ptr cloud( new pcl::PointCloud<PointT> () ); 00139 pcl::fromROSMsg (blob, *cloud); 00140 00141 signal_->operator () (cloud); 00142 } 00143 } 00144 #endif 00145 #endif