72     NODELET_ERROR (
"[onInit] Need a 'file_name' parameter to be set before continuing!");
    77     NODELET_ERROR (
"[onInit] Need a 'topic_name' parameter to be set before continuing!"); 
    81   int max_queue_size = 1;
    83   pnh_->getParam (
"max_queue_size", max_queue_size);
    85   ros::Publisher pub_output = pnh_->advertise<sensor_msgs::PointCloud2> (
"output", max_queue_size);
    87   NODELET_DEBUG (
"[onInit] Nodelet successfully created with the following parameters:\n"    95   output_ = boost::make_shared<PointCloud> (output);
   102     NODELET_DEBUG (
"Publishing data (%d points) on topic %s in frame %s.", 
output_->width * 
output_->height, pnh_->resolveName (
"output").c_str (), 
output_->header.frame_id.c_str ());
 PointCloudPtr output_
The output point cloud dataset containing the points loaded from the file. 
#define NODELET_ERROR(...)
std::string topic_name_
The name of the topic that contains the PointCloud data. 
void open(std::string const &filename, uint32_t mode=bagmode::Read)
BAG PointCloud file format reader. 
BAGReader()
Empty constructor. 
std::string file_name_
The name of the BAG file that contains the PointCloud data. 
sensor_msgs::PointCloud2 PointCloud
rosbag::Bag bag_
The BAG object. 
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. 
ros::NodeHandle & getMTPrivateNodeHandle() const
void publish(const boost::shared_ptr< M > &message) const
PointCloud::ConstPtr PointCloudConstPtr
void addQuery(Bag const &bag, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX)
rosbag::View view_
The BAG view object. 
PointCloudConstPtr getNextCloud()
Get the next point cloud dataset in the BAG file. 
rosbag::View::iterator it_
The BAG view iterator object. 
ROSCPP_DECL void spinOnce()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define NODELET_DEBUG(...)
double publish_rate_
The publishing interval in seconds. Set to 0 to publish once (default).