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. 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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
typedef sensor_msgs::PointCloud2 pcl_ros::BAGReader::PointCloud |
typedef PointCloud::ConstPtr pcl_ros::BAGReader::PointCloudConstPtr |
typedef PointCloud::Ptr pcl_ros::BAGReader::PointCloudPtr |
|
inline |
|
inline |
|
inline |
|
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.
|
inline |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |