|
Point Cloud Library (PCL)
1.5.1
|
Point Cloud Data (FILE) file format reader interface. More...
#include <pcl/io/file_io.h>

Public Member Functions | |
| FileReader () | |
| empty constructor | |
| virtual | ~FileReader () |
| empty destructor | |
| virtual int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, int &data_type, int &data_idx)=0 |
| Read a point cloud data header from a FILE file. | |
| virtual int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version)=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) |
| 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) |
| Read a point cloud data from any FILE file, and convert it to the given template format. | |
Point Cloud Data (FILE) file format reader interface.
Any (FILE) format file reader should implement its virtual methodes.
| pcl::FileReader::FileReader | ( | ) | [inline] |
| virtual pcl::FileReader::~FileReader | ( | ) | [inline, virtual] |
| virtual int pcl::FileReader::read | ( | const std::string & | file_name, |
| sensor_msgs::PointCloud2 & | cloud, | ||
| Eigen::Vector4f & | origin, | ||
| Eigen::Quaternionf & | orientation, | ||
| int & | file_version | ||
| ) | [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) |
Implemented in pcl::PCDReader, and pcl::PLYReader.
| int pcl::FileReader::read | ( | const std::string & | file_name, |
| sensor_msgs::PointCloud2 & | cloud | ||
| ) | [inline] |
Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a sensor_msgs/PointCloud2.
FILE_V6 will generate a warning.
| [in] | file_name | the name of the file containing the actual PointCloud data |
| [out] | cloud | the resultant PointCloud message read from disk |
Reimplemented in pcl::PCDReader, and pcl::PLYReader.
| int pcl::FileReader::read | ( | const std::string & | file_name, |
| pcl::PointCloud< PointT > & | cloud | ||
| ) | [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 |
Reimplemented in pcl::PCDReader, and pcl::PLYReader.
| 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, | ||
| int & | data_idx | ||
| ) | [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:
| [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 |
Implemented in pcl::PLYReader, and pcl::PCDReader.
1.8.0