Public Types | Public Member Functions | Private Attributes
pcl_ros::BAGReader Class Reference

BAG PointCloud file format reader. More...

#include <bag_io.h>

Inheritance diagram for pcl_ros::BAGReader:
Inheritance graph
[legend]

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 52 of file bag_io.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_ros::BAGReader::PointCloud

Definition at line 55 of file bag_io.h.

Definition at line 57 of file bag_io.h.

Definition at line 56 of file bag_io.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 60 of file bag_io.h.


Member Function Documentation

void pcl_ros::BAGReader::close ( ) [inline]

Close an open BAG file.

Definition at line 92 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 74 of file bag_io.h.

Get the publishing rate in seconds.

Definition at line 68 of file bag_io.h.

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.

Parameters:
file_namethe BAG file to open
topic_namethe 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_ratethe publishing rate in seconds

Definition at line 65 of file bag_io.h.


Member Data Documentation

The BAG object.

Definition at line 105 of file bag_io.h.

std::string pcl_ros::BAGReader::file_name_ [private]

The name of the BAG file that contains the PointCloud data.

Definition at line 117 of file bag_io.h.

The BAG view iterator object.

Definition at line 111 of file bag_io.h.

The output point cloud dataset containing the points loaded from the file.

Definition at line 120 of file bag_io.h.

The publishing interval in seconds. Set to 0 to publish once (default).

Definition at line 102 of file bag_io.h.

std::string pcl_ros::BAGReader::topic_name_ [private]

The name of the topic that contains the PointCloud data.

Definition at line 114 of file bag_io.h.

The BAG view object.

Definition at line 108 of file bag_io.h.


The documentation for this class was generated from the following files:


pcl_ros
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:22:24