Point Cloud Data (FILE) file format reader interface. Any (FILE) format file reader should implement its virtual methodes. More...
#include <file_io.h>
Public Member Functions | |
FileReader () | |
empty constructor | |
virtual int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, const int offset=0)=0 |
Read a point cloud data from a FILE file and store it into a sensor_msgs/PointCloud2. | |
int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const int offset=0) |
Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a sensor_msgs/PointCloud2. | |
template<typename PointT > | |
int | read (const std::string &file_name, pcl::PointCloud< PointT > &cloud, const int offset=0) |
Read a point cloud data from any FILE file, and convert it to the given template format. | |
virtual int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, int &data_type, unsigned int &data_idx, const int offset=0)=0 |
Read a point cloud data header from a FILE file. | |
virtual | ~FileReader () |
empty destructor |
Point Cloud Data (FILE) file format reader interface. Any (FILE) format file reader should implement its virtual methodes.
Definition at line 54 of file io/include/pcl/io/file_io.h.
pcl::FileReader::FileReader | ( | ) | [inline] |
empty constructor
Definition at line 58 of file io/include/pcl/io/file_io.h.
virtual pcl::FileReader::~FileReader | ( | ) | [inline, virtual] |
empty destructor
Definition at line 60 of file io/include/pcl/io/file_io.h.
virtual int pcl::FileReader::read | ( | const std::string & | file_name, |
sensor_msgs::PointCloud2 & | cloud, | ||
Eigen::Vector4f & | origin, | ||
Eigen::Quaternionf & | orientation, | ||
int & | file_version, | ||
const int | offset = 0 |
||
) | [pure virtual] |
Read a point cloud data from a FILE file and store it into a sensor_msgs/PointCloud2.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[out] | origin | the sensor acquisition origin (only for > FILE_V7 - null if not present) |
[out] | orientation | the sensor acquisition orientation (only for > FILE_V7 - identity if not present) |
[out] | file_version | the FILE version of the file (either FILE_V6 or FILE_V7) |
[in] | offset | the offset in the file where to expect the true header to begin. One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple files: TAR files always add a 512 byte header in front of the actual file, so set the offset to the next byte after the header (e.g., 513). |
Implemented in pcl::PCDReader, and pcl::PLYReader.
int pcl::FileReader::read | ( | const std::string & | file_name, |
sensor_msgs::PointCloud2 & | cloud, | ||
const int | offset = 0 |
||
) | [inline] |
Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a sensor_msgs/PointCloud2.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[in] | offset | the offset in the file where to expect the true header to begin. One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple files: TAR files always add a 512 byte header in front of the actual file, so set the offset to the next byte after the header (e.g., 513). |
Reimplemented in pcl::PCDReader, and pcl::PLYReader.
Definition at line 122 of file io/include/pcl/io/file_io.h.
int pcl::FileReader::read | ( | const std::string & | file_name, |
pcl::PointCloud< PointT > & | cloud, | ||
const int | offset = 0 |
||
) | [inline] |
Read a point cloud data from any FILE file, and convert it to the given template format.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[in] | offset | the offset in the file where to expect the true header to begin. One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple files: TAR files always add a 512 byte header in front of the actual file, so set the offset to the next byte after the header (e.g., 513). |
Reimplemented in pcl::PCDReader, and pcl::PLYReader.
Definition at line 140 of file io/include/pcl/io/file_io.h.
virtual int pcl::FileReader::readHeader | ( | const std::string & | file_name, |
sensor_msgs::PointCloud2 & | cloud, | ||
Eigen::Vector4f & | origin, | ||
Eigen::Quaternionf & | orientation, | ||
int & | file_version, | ||
int & | data_type, | ||
unsigned int & | data_idx, | ||
const int | offset = 0 |
||
) | [pure virtual] |
Read a point cloud data header from a FILE file.
Load only the meta information (number of points, their types, etc), and not the points themselves, from a given FILE file. Useful for fast evaluation of the underlying data structure.
Returns: * < 0 (-1) on error * > 0 on success
[in] | file_name | the name of the file to load |
[out] | cloud | the resultant point cloud dataset (only the header will be filled) |
[out] | origin | the sensor acquisition origin (only for > FILE_V7 - null if not present) |
[out] | orientation | the sensor acquisition orientation (only for > FILE_V7 - identity if not present) |
[out] | file_version | the FILE version of the file (either FILE_V6 or FILE_V7) |
[out] | data_type | the type of data (binary data=1, ascii=0, etc) |
[out] | data_idx | the offset of cloud data within the file |
[in] | offset | the offset in the file where to expect the true header to begin. One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple files: TAR files always add a 512 byte header in front of the actual file, so set the offset to the next byte after the header (e.g., 513). |
Implemented in pcl::PLYReader, and pcl::PCDReader.