46 #include <pcl/io/pcd_io.h> 
   83       if ((cloud->width * cloud->height) == 0)
 
   86       ROS_INFO (
"Received %d data points in frame %s with the following fields: %s",
 
   87                 (
int)cloud->width * cloud->height,
 
   88                 cloud->header.frame_id.c_str (),
 
   91       Eigen::Vector4f v = Eigen::Vector4f::Zero ();
 
   92       Eigen::Quaternionf q = Eigen::Quaternionf::Identity ();
 
   93       if (!fixed_frame_.empty ()) {
 
   95           ROS_WARN(
"Could not get transform!");
 
   99         Eigen::Affine3d transform;
 
  101         v = Eigen::Vector4f::Zero ();
 
  102         v.head<3> () = transform.translation ().cast<
float> ();
 
  103         q = transform.rotation ().cast<
float> ();
 
  106       std::stringstream ss;
 
  109         ss << filename_ << 
".pcd";
 
  113         ss << prefix_ << cloud->header.stamp << 
".pcd";
 
  115       ROS_INFO (
"Data saved to %s", ss.str ().c_str ());
 
  122           writer.writeBinaryCompressed (ss.str (), *cloud, v, q);
 
  126           writer.writeBinary (ss.str (), *cloud, v, q);
 
  131         writer.writeASCII (ss.str (), *cloud, v, q, 8);
 
  141       if (priv_nh.
getParam (
"prefix", prefix_))
 
  145       else if (nh_.
getParam (
"prefix", prefix_))
 
  151       priv_nh.
getParam (
"fixed_frame", fixed_frame_);
 
  152       priv_nh.
getParam (
"binary", binary_);
 
  153       priv_nh.
getParam (
"compressed", compressed_);
 
  154       priv_nh.
getParam (
"filename", filename_);
 
  176       cloud_topic_ = 
"input";
 
  179       ROS_INFO (
"Listening for incoming data on topic %s",