Public Types | Public Member Functions | Private Attributes | List of all members
pcl_ros::BAGReader Class Reference

BAG PointCloud file format reader. More...

#include <bag_io.h>

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

Public Types

typedef sensor_msgs::PointCloud2 PointCloud
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 

Public Member Functions

 BAGReader ()
 Empty constructor. More...
 
void close ()
 Close an open BAG file. More...
 
PointCloudConstPtr getNextCloud ()
 Get the next point cloud dataset in the BAG file. More...
 
double getPublishRate ()
 Get the publishing rate in seconds. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
bool open (const std::string &file_name, const std::string &topic_name)
 Open a BAG file for reading and select a specified topic. More...
 
void setPublishRate (double publish_rate)
 Set the publishing rate in seconds. More...
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Attributes

rosbag::Bag bag_
 The BAG object. More...
 
std::string file_name_
 The name of the BAG file that contains the PointCloud data. More...
 
rosbag::View::iterator it_
 The BAG view iterator object. More...
 
PointCloudPtr output_
 The output point cloud dataset containing the points loaded from the file. More...
 
double publish_rate_
 The publishing interval in seconds. Set to 0 to publish once (default). More...
 
std::string topic_name_
 The name of the topic that contains the PointCloud data. More...
 
rosbag::View view_
 The BAG view object. More...
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

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.

typedef PointCloud::ConstPtr pcl_ros::BAGReader::PointCloudConstPtr

Definition at line 57 of file bag_io.h.

typedef PointCloud::Ptr pcl_ros::BAGReader::PointCloudPtr

Definition at line 56 of file bag_io.h.

Constructor & Destructor Documentation

pcl_ros::BAGReader::BAGReader ( )
inline

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.

PointCloudConstPtr pcl_ros::BAGReader::getNextCloud ( )
inline

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.

double pcl_ros::BAGReader::getPublishRate ( )
inline

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

rosbag::Bag pcl_ros::BAGReader::bag_
private

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.

rosbag::View::iterator pcl_ros::BAGReader::it_
private

The BAG view iterator object.

Definition at line 111 of file bag_io.h.

PointCloudPtr pcl_ros::BAGReader::output_
private

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

Definition at line 120 of file bag_io.h.

double pcl_ros::BAGReader::publish_rate_
private

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.

rosbag::View pcl_ros::BAGReader::view_
private

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, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18