39 #include <pcl/common/transforms.h>
41 #include <pcl/io/pcd_io.h>
42 #include <pcl/io/io.h>
48 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
49 DiagnosticNodelet::onInit();
50 std::string file_name;
51 pnh_->param(
"pcd_file", file_name, std::string(
""));
56 pub_cloud_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
70 const geometry_msgs::PoseStamped::ConstPtr& pose_stamped)
72 vital_checker_->poke();
74 Eigen::Affine3f pose_eigen;
76 sensor_msgs::PointCloud2 ros_out;
77 Eigen::Matrix4f
transform = pose_eigen.matrix();
79 ros_out.header = pose_stamped->header;