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 <nodelet/nodelet.h>
42 #include <Eigen/Core>
43 #include <sensor_msgs/PointCloud2.h>
44 #include <rosbag/bag.h>
45 #include <rosbag/view.h>
46 
47 namespace pcl_ros
48 {
50 
54  {
55  public:
56  typedef sensor_msgs::PointCloud2 PointCloud;
57  typedef PointCloud::Ptr PointCloudPtr;
58  typedef PointCloud::ConstPtr PointCloudConstPtr;
59 
61  BAGReader () : publish_rate_ (0), output_ ()/*, cloud_received_ (false)*/ {};
62 
66  inline void setPublishRate (double publish_rate) { publish_rate_ = publish_rate; }
67 
69  inline double getPublishRate () { return (publish_rate_); }
70 
74  inline PointCloudConstPtr
76  {
77  if (it_ != view_.end ())
78  {
79  output_ = it_->instantiate<sensor_msgs::PointCloud2> ();
80  ++it_;
81  }
82  return (output_);
83  }
84 
89  bool open (const std::string &file_name, const std::string &topic_name);
90 
92  inline void
93  close ()
94  {
95  bag_.close ();
96  }
97 
99  virtual void onInit ();
100 
101  private:
104 
107 
110 
113 
115  std::string topic_name_;
116 
118  std::string file_name_;
119 
122 
124  //bool cloud_received_;
125  public:
126  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
127  };
128 
129 }
130 
131 #endif //#ifndef PCL_ROS_IO_BAG_IO_H_
pcl_ros::BAGReader::getNextCloud
PointCloudConstPtr getNextCloud()
Get the next point cloud dataset in the BAG file.
Definition: bag_io.h:75
pcl_ros::BAGReader::PointCloudConstPtr
PointCloud::ConstPtr PointCloudConstPtr
Definition: bag_io.h:58
PointCloudConstPtr
PointCloud::ConstPtr PointCloudConstPtr
Definition: bag_to_pcd.cpp:57
rosbag::Bag
pcl_ros::BAGReader::BAGReader
BAGReader()
Empty constructor.
Definition: bag_io.h:61
pcl_ros
Definition: boundary.h:46
pcl_ros::BAGReader::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: bag_io.h:56
pcl_ros::BAGReader::output_
PointCloudPtr output_
The output point cloud dataset containing the points loaded from the file.
Definition: bag_io.h:121
pcl_ros::BAGReader
BAG PointCloud file format reader.
Definition: bag_io.h:53
pcl_ros::BAGReader::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: bag_io.cpp:65
rosbag::Bag::close
void close()
bag.h
pcl_ros::BAGReader::view_
rosbag::View view_
The BAG view object.
Definition: bag_io.h:109
pcl_ros::BAGReader::topic_name_
std::string topic_name_
The name of the topic that contains the PointCloud data.
Definition: bag_io.h:115
pcl_ros::BAGReader::close
void close()
Close an open BAG file.
Definition: bag_io.h:93
pcl_ros::BAGReader::PointCloudPtr
PointCloud::Ptr PointCloudPtr
Definition: bag_io.h:57
pcl_ros::BAGReader::publish_rate_
double publish_rate_
The publishing interval in seconds. Set to 0 to publish once (default).
Definition: bag_io.h:103
pcl_ros::BAGReader::it_
rosbag::View::iterator it_
The BAG view iterator object.
Definition: bag_io.h:112
pcl_ros::BAGReader::setPublishRate
void setPublishRate(double publish_rate)
Set the publishing rate in seconds.
Definition: bag_io.h:66
view.h
pcl_ros::BAGReader::file_name_
std::string file_name_
The name of the BAG file that contains the PointCloud data.
Definition: bag_io.h:118
rosbag::View
nodelet::Nodelet
pcl_ros::BAGReader::open
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:44
nodelet.h
pcl_ros::BAGReader::bag_
rosbag::Bag bag_
The BAG object.
Definition: bag_io.h:106
rosbag::View::end
iterator end()
pcl_ros::BAGReader::getPublishRate
double getPublishRate()
Get the publishing rate in seconds.
Definition: bag_io.h:69


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40