Point Cloud Data (FILE) file format writer. Any (FILE) format file reader should implement its virtual methodes. More...
#include <file_io.h>

Public Member Functions | |
| FileWriter () | |
| Empty constructor. | |
| virtual int | write (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary=false)=0 |
| Save point cloud data to a FILE file containing n-D points. | |
| int | write (const std::string &file_name, const sensor_msgs::PointCloud2::ConstPtr &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary=false) |
| Save point cloud data to a FILE file containing n-D points. | |
| template<typename PointT > | |
| int | write (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const bool binary=false) |
| Save point cloud data to a FILE file containing n-D points. | |
| virtual | ~FileWriter () |
| Empty destructor. | |
Point Cloud Data (FILE) file format writer. Any (FILE) format file reader should implement its virtual methodes.
Definition at line 160 of file io/include/pcl/io/file_io.h.
| pcl::FileWriter::FileWriter | ( | ) | [inline] |
Empty constructor.
Definition at line 164 of file io/include/pcl/io/file_io.h.
| virtual pcl::FileWriter::~FileWriter | ( | ) | [inline, virtual] |
Empty destructor.
Definition at line 167 of file io/include/pcl/io/file_io.h.
| virtual int pcl::FileWriter::write | ( | const std::string & | file_name, |
| const sensor_msgs::PointCloud2 & | cloud, | ||
| const Eigen::Vector4f & | origin = Eigen::Vector4f::Zero(), |
||
| const Eigen::Quaternionf & | orientation = Eigen::Quaternionf::Identity(), |
||
| const bool | binary = false |
||
| ) | [pure virtual] |
Save point cloud data to a FILE file containing n-D points.
| [in] | file_name | the output file name |
| [in] | cloud | the point cloud data message |
| [in] | origin | the sensor acquisition origin |
| [in] | orientation | the sensor acquisition orientation |
| [in] | binary | set to true if the file is to be written in a binary FILE format, false (default) for ASCII |
Implemented in pcl::PLYWriter, and pcl::PCDWriter.
| int pcl::FileWriter::write | ( | const std::string & | file_name, |
| const sensor_msgs::PointCloud2::ConstPtr & | cloud, | ||
| const Eigen::Vector4f & | origin = Eigen::Vector4f::Zero (), |
||
| const Eigen::Quaternionf & | orientation = Eigen::Quaternionf::Identity (), |
||
| const bool | binary = false |
||
| ) | [inline] |
Save point cloud data to a FILE file containing n-D points.
| [in] | file_name | the output file name |
| [in] | cloud | the point cloud data message (boost shared pointer) |
| [in] | binary | set to true if the file is to be written in a binary FILE format, false (default) for ASCII |
| [in] | origin | the sensor acquisition origin |
| [in] | orientation | the sensor acquisition orientation |
Reimplemented in pcl::PCDWriter.
Definition at line 192 of file io/include/pcl/io/file_io.h.
| int pcl::FileWriter::write | ( | const std::string & | file_name, |
| const pcl::PointCloud< PointT > & | cloud, | ||
| const bool | binary = false |
||
| ) | [inline] |
Save point cloud data to a FILE file containing n-D points.
| [in] | file_name | the output file name |
| [in] | cloud | the pcl::PointCloud data |
| [in] | binary | set to true if the file is to be written in a binary FILE format, false (default) for ASCII |
Reimplemented in pcl::PCDWriter.
Definition at line 207 of file io/include/pcl/io/file_io.h.