38 #ifndef PCL_ROS_IO_BAG_IO_H_ 39 #define PCL_ROS_IO_BAG_IO_H_ 42 #include <sensor_msgs/PointCloud2.h> 73 inline PointCloudConstPtr
78 output_ =
it_->instantiate<sensor_msgs::PointCloud2> ();
88 bool open (
const std::string &file_name,
const std::string &topic_name);
125 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
130 #endif //#ifndef PCL_ROS_IO_BAG_IO_H_ PointCloudPtr output_
The output point cloud dataset containing the points loaded from the file.
PointCloud::Ptr PointCloudPtr
void close()
Close an open BAG file.
std::string topic_name_
The name of the topic that contains the PointCloud data.
BAG PointCloud file format reader.
BAGReader()
Empty constructor.
double getPublishRate()
Get the publishing rate in seconds.
std::string file_name_
The name of the BAG file that contains the PointCloud data.
sensor_msgs::PointCloud2 PointCloud
rosbag::Bag bag_
The BAG object.
virtual void onInit()
Nodelet initialization routine.
bool open(const std::string &file_name, const std::string &topic_name)
Open a BAG file for reading and select a specified topic.
PointCloud::ConstPtr PointCloudConstPtr
rosbag::View view_
The BAG view object.
PointCloudConstPtr getNextCloud()
Get the next point cloud dataset in the BAG file.
rosbag::View::iterator it_
The BAG view iterator object.
void setPublishRate(double publish_rate)
Set the publishing rate in seconds.
double publish_rate_
The publishing interval in seconds. Set to 0 to publish once (default).