bag_io.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: bag_io.h 35471 2011-01-25 06:50:00Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_IO_BAG_IO_H_
39 #define PCL_ROS_IO_BAG_IO_H_
40 
41 #include <pcl_ros/pcl_nodelet.h>
42 #include <sensor_msgs/PointCloud2.h>
43 #include <rosbag/bag.h>
44 #include <rosbag/view.h>
45 
46 namespace pcl_ros
47 {
49 
53  {
54  public:
55  typedef sensor_msgs::PointCloud2 PointCloud;
56  typedef PointCloud::Ptr PointCloudPtr;
57  typedef PointCloud::ConstPtr PointCloudConstPtr;
58 
60  BAGReader () : publish_rate_ (0), output_ ()/*, cloud_received_ (false)*/ {};
61 
65  inline void setPublishRate (double publish_rate) { publish_rate_ = publish_rate; }
66 
68  inline double getPublishRate () { return (publish_rate_); }
69 
73  inline PointCloudConstPtr
75  {
76  if (it_ != view_.end ())
77  {
78  output_ = it_->instantiate<sensor_msgs::PointCloud2> ();
79  ++it_;
80  }
81  return (output_);
82  }
83 
88  bool open (const std::string &file_name, const std::string &topic_name);
89 
91  inline void
92  close ()
93  {
94  bag_.close ();
95  }
96 
98  virtual void onInit ();
99 
100  private:
103 
106 
109 
112 
114  std::string topic_name_;
115 
117  std::string file_name_;
118 
120  PointCloudPtr output_;
121 
123  //bool cloud_received_;
124  public:
125  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
126  };
127 
128 }
129 
130 #endif //#ifndef PCL_ROS_IO_BAG_IO_H_
PointCloudPtr output_
The output point cloud dataset containing the points loaded from the file.
Definition: bag_io.h:120
PointCloud::Ptr PointCloudPtr
Definition: bag_io.h:56
void close()
Close an open BAG file.
Definition: bag_io.h:92
std::string topic_name_
The name of the topic that contains the PointCloud data.
Definition: bag_io.h:114
BAG PointCloud file format reader.
Definition: bag_io.h:52
BAGReader()
Empty constructor.
Definition: bag_io.h:60
double getPublishRate()
Get the publishing rate in seconds.
Definition: bag_io.h:68
std::string file_name_
The name of the BAG file that contains the PointCloud data.
Definition: bag_io.h:117
sensor_msgs::PointCloud2 PointCloud
Definition: bag_io.h:55
rosbag::Bag bag_
The BAG object.
Definition: bag_io.h:105
virtual void onInit()
Nodelet initialization routine.
Definition: bag_io.cpp:64
void close()
bool open(const std::string &file_name, const std::string &topic_name)
Open a BAG file for reading and select a specified topic.
Definition: bag_io.cpp:43
PointCloud::ConstPtr PointCloudConstPtr
Definition: bag_io.h:57
rosbag::View view_
The BAG view object.
Definition: bag_io.h:108
PointCloudConstPtr getNextCloud()
Get the next point cloud dataset in the BAG file.
Definition: bag_io.h:74
iterator end()
rosbag::View::iterator it_
The BAG view iterator object.
Definition: bag_io.h:111
void setPublishRate(double publish_rate)
Set the publishing rate in seconds.
Definition: bag_io.h:65
double publish_rate_
The publishing interval in seconds. Set to 0 to publish once (default).
Definition: bag_io.h:102


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18