Added option to save pointclouds in binary and binary compressed format
This commit is contained in:
parent
d7adb41971
commit
10727ec650
@ -63,6 +63,8 @@ class PointCloudToPCD
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
std::string prefix_;
|
std::string prefix_;
|
||||||
|
bool binary_;
|
||||||
|
bool compressed_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
string cloud_topic_;
|
string cloud_topic_;
|
||||||
@ -86,12 +88,30 @@ class PointCloudToPCD
|
|||||||
ss << prefix_ << cloud->header.stamp << ".pcd";
|
ss << prefix_ << cloud->header.stamp << ".pcd";
|
||||||
ROS_INFO ("Data saved to %s", ss.str ().c_str ());
|
ROS_INFO ("Data saved to %s", ss.str ().c_str ());
|
||||||
|
|
||||||
pcl::io::savePCDFile (ss.str (), *cloud, Eigen::Vector4f::Zero (),
|
pcl::PCDWriter writer;
|
||||||
Eigen::Quaternionf::Identity (), false);
|
if(binary_)
|
||||||
|
{
|
||||||
|
if(compressed_)
|
||||||
|
{
|
||||||
|
writer.writeBinaryCompressed (ss.str (), *cloud, Eigen::Vector4f::Zero (),
|
||||||
|
Eigen::Quaternionf::Identity ());
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
writer.writeBinary (ss.str (), *cloud, Eigen::Vector4f::Zero (),
|
||||||
|
Eigen::Quaternionf::Identity ());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
writer.writeASCII (ss.str (), *cloud, Eigen::Vector4f::Zero (),
|
||||||
|
Eigen::Quaternionf::Identity (), 8);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
PointCloudToPCD ()
|
PointCloudToPCD () : binary_(false), compressed_(false)
|
||||||
{
|
{
|
||||||
// Check if a prefix parameter is defined for output file names.
|
// Check if a prefix parameter is defined for output file names.
|
||||||
ros::NodeHandle priv_nh("~");
|
ros::NodeHandle priv_nh("~");
|
||||||
@ -105,6 +125,24 @@ class PointCloudToPCD
|
|||||||
<< prefix_);
|
<< prefix_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
priv_nh.getParam ("binary", binary_);
|
||||||
|
priv_nh.getParam ("compressed", compressed_);
|
||||||
|
if(binary_)
|
||||||
|
{
|
||||||
|
if(compressed_)
|
||||||
|
{
|
||||||
|
ROS_INFO_STREAM ("Saving as binary compressed PCD");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ROS_INFO_STREAM ("Saving as binary PCD");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ROS_INFO_STREAM ("Saving as binary PCD");
|
||||||
|
}
|
||||||
|
|
||||||
cloud_topic_ = "input";
|
cloud_topic_ = "input";
|
||||||
|
|
||||||
sub_ = nh_.subscribe (cloud_topic_, 1, &PointCloudToPCD::cloud_cb, this);
|
sub_ = nh_.subscribe (cloud_topic_, 1, &PointCloudToPCD::cloud_cb, this);
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user