|
Point Cloud Library (PCL)
1.4.0
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2011, 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__ 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 { 00054 class PCL_EXPORTS PCDGrabberBase : public Grabber 00055 { 00056 public: 00062 PCDGrabberBase (const std::string& pcd_file, float frames_per_second, bool repeat); 00063 00070 PCDGrabberBase (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat); 00074 virtual ~PCDGrabberBase () throw (); 00078 virtual void start (); 00082 virtual void stop (); 00087 virtual bool isRunning () const; 00092 virtual std::string getName () const; 00096 virtual void rewind (); 00097 00101 virtual float getFramesPerSecond () const; 00102 00106 bool isRepeatOn () const; 00107 00108 private: 00109 virtual void publish (const sensor_msgs::PointCloud2& blob) const = 0; 00110 00111 // to seperate and hide the implementation from interface: PIMPL 00112 struct PCDGrabberImpl; 00113 PCDGrabberImpl* impl_; 00114 }; 00115 00119 template <typename T> class PointCloud; 00120 //class sensor_msgs::PointCloud2; 00121 template <typename PointT> class PCDGrabber : public PCDGrabberBase 00122 { 00123 public: 00124 PCDGrabber (const std::string& pcd_path, float frames_per_second = 0, bool repeat = false); 00125 PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second = 0, bool repeat = false); 00126 protected: 00127 virtual void publish (const sensor_msgs::PointCloud2& blob) const; 00128 boost::signals2::signal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>* signal_; 00129 }; 00130 00131 template<typename PointT> 00132 PCDGrabber<PointT>::PCDGrabber (const std::string& pcd_path, float frames_per_second, bool repeat) 00133 : PCDGrabberBase ( pcd_path, frames_per_second, repeat) 00134 { 00135 signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>(); 00136 } 00137 00138 template<typename PointT> 00139 PCDGrabber<PointT>::PCDGrabber (const std::vector<std::string>& pcd_files, float frames_per_second, bool repeat) 00140 : PCDGrabberBase ( pcd_files, frames_per_second, repeat) 00141 { 00142 signal_ = createSignal<void (const boost::shared_ptr<const pcl::PointCloud<PointT> >&)>(); 00143 } 00144 00145 template<typename PointT> 00146 void PCDGrabber<PointT>::publish (const sensor_msgs::PointCloud2& blob) const 00147 { 00148 typename pcl::PointCloud<PointT>::Ptr cloud( new pcl::PointCloud<PointT> () ); 00149 pcl::fromROSMsg (blob, *cloud); 00150 00151 signal_->operator () (cloud); 00152 } 00153 } 00154 #endif
1.7.6.1