BAG PointCloud file format reader. More...
#include <bag_io.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
Public Member Functions | |
BAGReader () | |
Empty constructor. | |
void | close () |
Close an open BAG file. | |
PointCloudConstPtr | getNextCloud () |
Get the next point cloud dataset in the BAG file. | |
double | getPublishRate () |
Get the publishing rate in seconds. | |
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. | |
void | setPublishRate (double publish_rate) |
Set the publishing rate in seconds. | |
Private Attributes | |
rosbag::Bag | bag_ |
The BAG object. | |
std::string | file_name_ |
The name of the BAG file that contains the PointCloud data. | |
rosbag::View::iterator | it_ |
The BAG view iterator object. | |
PointCloudPtr | output_ |
The output point cloud dataset containing the points loaded from the file. | |
double | publish_rate_ |
The publishing interval in seconds. Set to 0 to publish once (default). | |
std::string | topic_name_ |
The name of the topic that contains the PointCloud data. | |
rosbag::View | view_ |
The BAG view object. |
typedef sensor_msgs::PointCloud2 pcl_ros::BAGReader::PointCloud |
pcl_ros::BAGReader::BAGReader | ( | ) | [inline] |
void pcl_ros::BAGReader::close | ( | ) | [inline] |
PointCloudConstPtr pcl_ros::BAGReader::getNextCloud | ( | ) | [inline] |
double pcl_ros::BAGReader::getPublishRate | ( | ) | [inline] |
void pcl_ros::BAGReader::onInit | ( | ) | [virtual] |
Nodelet initialization routine.
Implements nodelet::Nodelet.
Definition at line 64 of file bag_io.cpp.
bool pcl_ros::BAGReader::open | ( | const std::string & | file_name, |
const std::string & | topic_name | ||
) |
Open a BAG file for reading and select a specified topic.
file_name | the BAG file to open |
topic_name | the topic that we want to read data from |
Definition at line 43 of file bag_io.cpp.
void pcl_ros::BAGReader::setPublishRate | ( | double | publish_rate | ) | [inline] |
rosbag::Bag pcl_ros::BAGReader::bag_ [private] |
std::string pcl_ros::BAGReader::file_name_ [private] |
PointCloudPtr pcl_ros::BAGReader::output_ [private] |
double pcl_ros::BAGReader::publish_rate_ [private] |
std::string pcl_ros::BAGReader::topic_name_ [private] |
rosbag::View pcl_ros::BAGReader::view_ [private] |