37 #include <sensor_msgs/PointCloud2.h> 42 #include <pcl/io/io.h> 43 #include <Eigen/Geometry> 54 pcl::PCLPointCloud2::ConstPtr
cloud;
55 cloud = ros::topic::waitForMessage<pcl::PCLPointCloud2>(
"input", *
pnh_);
56 if ((cloud->width * cloud->height) == 0)
61 ROS_INFO (
"Received %d data points in frame %s with the following fields: %s",
62 (
int)cloud->width * cloud->height,
63 cloud->header.frame_id.c_str (),
66 Eigen::Vector4f v = Eigen::Vector4f::Zero ();
67 Eigen::Quaternionf
q = Eigen::Quaternionf::Identity ();
70 ROS_WARN(
"Could not get transform!");
75 Eigen::Affine3d transform;
77 v = Eigen::Vector4f::Zero ();
78 v.head<3> () = transform.translation ().cast<
float> ();
79 q = transform.rotation ().cast<
float> ();
83 ss <<
prefix_ << cloud->header.stamp <<
".pcd";
84 ROS_INFO (
"Data saved to %s", ss.str ().c_str ());
86 pcl::PCDWriter writer;
91 writer.writeBinaryCompressed (ss.str (), *
cloud, v, q);
95 writer.writeBinary (ss.str (), *
cloud, v, q);
100 writer.writeASCII (ss.str (), *
cloud, v, q, 8);
106 PCLNodelet::onInit();
107 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
109 srv_->setCallback (f);
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
PointCloudToPCDConfig Config
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PointCloudToPCD, nodelet::Nodelet)
virtual ~PointCloudToPCD()
#define ROS_INFO_STREAM(args)
tf::TransformListener * tf_listener_
virtual void timerCallback(const ros::TimerEvent &event)
static tf::TransformListener * getInstance()
virtual void configCallback(Config &config, uint32_t level)
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)