Point Cloud Data (PCD) file format reader. More...
#include <pcd_io.h>

| Public Types | |
| enum | { PCD_V6 = 0, PCD_V7 = 1 } | 
| Various PCD file versions.  More... | |
| Public Member Functions | |
| PCDReader () | |
| int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, const int offset=0) | 
| Read a point cloud data from a PCD 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 PCD (PCD_V6) 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 PCD file, and convert it to the given template format. | |
| int | readEigen (const std::string &file_name, pcl::PointCloud< Eigen::MatrixXf > &cloud, const int offset=0) | 
| Read a point cloud data from any PCD file, and convert it to a pcl::PointCloud<Eigen::MatrixXf> format. | |
| int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version, int &data_type, unsigned int &data_idx, const int offset=0) | 
| Read a point cloud data header from a PCD file. | |
| int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const int offset=0) | 
| Read a point cloud data header from a PCD file. | |
| int | readHeaderEigen (const std::string &file_name, pcl::PointCloud< Eigen::MatrixXf > &cloud, int &pcd_version, int &data_type, unsigned int &data_idx, const int offset=0) | 
| Read a point cloud data header from a PCD file. | |
| ~PCDReader () | |
| anonymous enum | 
Various PCD file versions.
PCD_V6 represents PCD files with version 0.6, which contain the following fields:
Everything that follows DATA is intepreted as data points and will be read accordingly.
PCD_V7 represents PCD files with version 0.7 and has an important addon: it adds sensor origin/orientation (aka viewpoint) information to a dataset through the use of a new header field:
| pcl::PCDReader::PCDReader | ( | ) |  [inline] | 
| pcl::PCDReader::~PCDReader | ( | ) |  [inline] | 
| int pcl::PCDReader::read | ( | const std::string & | file_name, | 
| sensor_msgs::PointCloud2 & | cloud, | ||
| Eigen::Vector4f & | origin, | ||
| Eigen::Quaternionf & | orientation, | ||
| int & | pcd_version, | ||
| const int | offset = 0 | ||
| ) |  [virtual] | 
Read a point cloud data from a PCD 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 > PCD_V7 - null if not present) | 
| [out] | orientation | the sensor acquisition orientation (only for > PCD_V7 - identity if not present) | 
| [out] | pcd_version | the PCD version of the file (either PCD_V6 or PCD_V7) | 
| [in] | offset | the offset of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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). | 
---[ Binary mode only We must re-open the file and read with mmap () for binary
---[ Binary compressed mode only
Implements pcl::FileReader.
Definition at line 881 of file pcd_io.cpp.
| int pcl::PCDReader::read | ( | const std::string & | file_name, | 
| sensor_msgs::PointCloud2 & | cloud, | ||
| const int | offset = 0 | ||
| ) | 
Read a point cloud data from a PCD (PCD_V6) 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 of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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 from pcl::FileReader.
Definition at line 1427 of file pcd_io.cpp.
| int pcl::PCDReader::read | ( | const std::string & | file_name, | 
| pcl::PointCloud< PointT > & | cloud, | ||
| const int | offset = 0 | ||
| ) |  [inline] | 
Read a point cloud data from any PCD 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 of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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 from pcl::FileReader.
| int pcl::PCDReader::readEigen | ( | const std::string & | file_name, | 
| pcl::PointCloud< Eigen::MatrixXf > & | cloud, | ||
| const int | offset = 0 | ||
| ) | 
Read a point cloud data from any PCD file, and convert it to a pcl::PointCloud<Eigen::MatrixXf> 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 of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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). | 
---[ Binary mode only We must re-open the file and read with mmap () for binary
---[ Binary compressed mode only
Definition at line 1243 of file pcd_io.cpp.
| int pcl::PCDReader::readHeader | ( | const std::string & | file_name, | 
| sensor_msgs::PointCloud2 & | cloud, | ||
| Eigen::Vector4f & | origin, | ||
| Eigen::Quaternionf & | orientation, | ||
| int & | pcd_version, | ||
| int & | data_type, | ||
| unsigned int & | data_idx, | ||
| const int | offset = 0 | ||
| ) |  [virtual] | 
Read a point cloud data header from a PCD file.
Load only the meta information (number of points, their types, etc), and not the points themselves, from a given PCD file. Useful for fast evaluation of the underlying data structure.
| [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 > PCD_V7 - null if not present) | 
| [out] | orientation | the sensor acquisition orientation (only for > PCD_V7 - identity if not present) | 
| [out] | pcd_version | the PCD version of the file (i.e., PCD_V6, PCD_V7) | 
| [out] | data_type | the type of data (0 = ASCII, 1 = Binary, 2 = Binary compressed) | 
| [out] | data_idx | the offset of cloud data within the file | 
| [in] | offset | the offset of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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). | 
Implements pcl::FileReader.
Definition at line 69 of file pcd_io.cpp.
| int pcl::PCDReader::readHeader | ( | const std::string & | file_name, | 
| sensor_msgs::PointCloud2 & | cloud, | ||
| const int | offset = 0 | ||
| ) | 
Read a point cloud data header from a PCD file.
Load only the meta information (number of points, their types, etc), and not the points themselves, from a given PCD file. Useful for fast evaluation of the underlying data structure.
| [in] | file_name | the name of the file to load | 
| [out] | cloud | the resultant point cloud dataset (only the header will be filled) | 
| [in] | offset | the offset of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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). | 
Definition at line 357 of file pcd_io.cpp.
| int pcl::PCDReader::readHeaderEigen | ( | const std::string & | file_name, | 
| pcl::PointCloud< Eigen::MatrixXf > & | cloud, | ||
| int & | pcd_version, | ||
| int & | data_type, | ||
| unsigned int & | data_idx, | ||
| const int | offset = 0 | ||
| ) | 
Read a point cloud data header from a PCD file.
Load only the meta information (number of points, their types, etc), and not the points themselves, from a given PCD file. Useful for fast evaluation of the underlying data structure.
| [in] | file_name | the name of the file to load | 
| [out] | cloud | the resultant point cloud dataset (only the properties will be filled) | 
| [out] | pcd_version | the PCD version of the file (either PCD_V6 or PCD_V7) | 
| [out] | data_type | the type of data (0 = ASCII, 1 = Binary, 2 = Binary compressed) | 
| [out] | data_idx | the offset of cloud data within the file | 
| [in] | offset | the offset of where to expect the PCD Header in the file (optional parameter). One usage example for setting the offset parameter is for reading data from a TAR "archive containing multiple PCD 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). | 
Definition at line 619 of file pcd_io.cpp.