Go to the documentation of this file.
70 if (!pnh_->getParam (
"file_name", file_name_))
72 NODELET_ERROR (
"[onInit] Need a 'file_name' parameter to be set before continuing!");
75 if (!pnh_->getParam (
"topic_name", topic_name_))
77 NODELET_ERROR (
"[onInit] Need a 'topic_name' parameter to be set before continuing!");
81 int max_queue_size = 1;
82 pnh_->getParam (
"publish_rate", publish_rate_);
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"
90 file_name_.c_str (), topic_name_.c_str ());
92 if (!open (file_name_, topic_name_))
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 ());
PointCloud::ConstPtr PointCloudConstPtr
#define NODELET_ERROR(...)
sensor_msgs::PointCloud2 PointCloud
BAG PointCloud file format reader.
virtual void onInit()
Nodelet initialization routine.
ROSCPP_DECL void spinOnce()
void publish(const boost::shared_ptr< M > &message) const
rosbag::View view_
The BAG view object.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rosbag::View::iterator it_
The BAG view iterator object.
void addQuery(Bag const &bag, boost::function< bool(ConnectionInfo const *)> query, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX)
bool open(const std::string &file_name, const std::string &topic_name)
Open a BAG file for reading and select a specified topic.
pcl_ros::BAGReader BAGReader
rosbag::Bag bag_
The BAG object.
void open(std::string const &filename, uint32_t mode=bagmode::Read)
#define NODELET_DEBUG(...)
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40