bag_io.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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  * $Id: bag_io.h 35471 2011-01-25 06:50:00Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_ROS_IO_BAG_IO_H_
00039 #define PCL_ROS_IO_BAG_IO_H_
00040 
00041 #include <pcl_ros/pcl_nodelet.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <rosbag/bag.h>
00044 #include <rosbag/view.h>
00045 
00046 namespace pcl_ros
00047 {
00049 
00052   class BAGReader: public nodelet::Nodelet
00053   {
00054     public:
00055       typedef sensor_msgs::PointCloud2 PointCloud;
00056       typedef PointCloud::Ptr PointCloudPtr;
00057       typedef PointCloud::ConstPtr PointCloudConstPtr;
00058 
00060       BAGReader () : publish_rate_ (0), output_ ()/*, cloud_received_ (false)*/ {};
00061 
00065       inline void setPublishRate (double publish_rate) { publish_rate_ = publish_rate; }
00066 
00068       inline double getPublishRate () { return (publish_rate_); }
00069 
00073       inline PointCloudConstPtr
00074         getNextCloud ()
00075       {
00076         if (it_ != view_.end ())
00077         {
00078           output_ = it_->instantiate<sensor_msgs::PointCloud2> ();
00079           ++it_;
00080         }
00081         return (output_);
00082       }
00083 
00088       bool open (const std::string &file_name, const std::string &topic_name);
00089 
00091       inline void 
00092         close ()
00093       {
00094         bag_.close ();
00095       }
00096 
00098       virtual void onInit ();
00099 
00100     private:
00102       double publish_rate_;
00103 
00105       rosbag::Bag bag_;
00106 
00108       rosbag::View view_;
00109 
00111       rosbag::View::iterator it_;
00112 
00114       std::string topic_name_;
00115 
00117       std::string file_name_;
00118 
00120       PointCloudPtr output_;
00121 
00123       //bool cloud_received_;
00124     public:
00125       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00126   };
00127 
00128 }
00129 
00130 #endif  //#ifndef PCL_ROS_IO_BAG_IO_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pcl_ros
Author(s): Maintained by Radu Bogdan Rusu
autogenerated on Tue Mar 5 2013 13:54:40