36 #include <jsk_topic_tools/log_utils.h>
38 #include <jsk_topic_tools/rosparam_utils.h>
39 #include <pcl/io/pcd_io.h>
40 #include <pcl/io/vtk_lib_io.h>
42 #include <boost/filesystem.hpp>
50 cloud_.reset(
new pcl::PointCloud<pcl::PointXYZRGB>);
52 ext_ = path.extension().string();
53 stem_ = path.stem().string();
70 sensor_msgs::PointCloud2
73 sensor_msgs::PointCloud2 ros_out;
75 ros_out.header.stamp =
stamp;
76 ros_out.header.frame_id =
stem_;
89 pub_cloud_ =
pnh_->advertise<sensor_msgs::PointCloud2>(
"cloud", 1);
90 if (!jsk_topic_tools::readVectorParameter(*
pnh_,
"models",
files_)
96 for (
size_t i = 0;
i<
files_.size();
i++) {
101 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
102 dynamic_reconfigure::Server<Config>::CallbackType
f =
105 srv_->setCallback (
f);
113 array_msg_.cloud_list[
i].header.stamp =
event.current_real;