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",
pcl_ros::PCDWriter PCDWriter
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
tf2_ros::Buffer tf_buffer_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void cloud_cb(const boost::shared_ptr< const pcl::PCLPointCloud2 > &cloud)
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
int main(int argc, char **argv)
bool getParam(const std::string &key, std::string &s) const
std::string resolveName(const std::string &name, bool remap=true) const
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
tf2_ros::TransformListener tf_listener_
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
Eigen::Isometry3d transformToEigen(const geometry_msgs::Transform &t)