pcl_ros::BAGReader Class Reference
BAG PointCloud file format reader.
More...
#include <bag_io.h>
List of all members.
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.
|
Detailed Description
BAG PointCloud file format reader.
- Author:
- Radu Bogdan Rusu
Definition at line 50 of file bag_io.h.
Member Typedef Documentation
Constructor & Destructor Documentation
pcl_ros::BAGReader::BAGReader |
( |
|
) |
[inline] |
Empty constructor.
Definition at line 52 of file bag_io.h.
Member Function Documentation
void pcl_ros::BAGReader::close |
( |
|
) |
[inline] |
Close an open BAG file.
Definition at line 84 of file bag_io.h.
Get the next point cloud dataset in the BAG file.
- Returns:
- the next point cloud dataset as read from the file
Definition at line 66 of file bag_io.h.
double pcl_ros::BAGReader::getPublishRate |
( |
|
) |
[inline] |
Get the publishing rate in seconds.
Definition at line 60 of file bag_io.h.
void pcl_ros::BAGReader::onInit |
( |
|
) |
[virtual] |
Nodelet initialization routine.
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.
- Parameters:
-
| 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] |
Set the publishing rate in seconds.
- Parameters:
-
| publish_rate | the publishing rate in seconds |
Definition at line 57 of file bag_io.h.
Member Data Documentation
The BAG object.
Definition at line 97 of file bag_io.h.
The name of the BAG file that contains the PointCloud data.
Definition at line 109 of file bag_io.h.
The BAG view iterator object.
Definition at line 103 of file bag_io.h.
The output point cloud dataset containing the points loaded from the file.
Definition at line 112 of file bag_io.h.
The publishing interval in seconds. Set to 0 to publish once (default).
Definition at line 94 of file bag_io.h.
The name of the topic that contains the PointCloud data.
Definition at line 106 of file bag_io.h.
The BAG view object.
Definition at line 100 of file bag_io.h.
The documentation for this class was generated from the following files: