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 | |
template<typename PointT > | |
int | read (const std::string &file_name, pcl::PointCloud< PointT > &cloud) |
Read a point cloud data from any PCD file, and convert it to the given template format. | |
int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud) |
Read a point cloud data from a PCD file (PCD_V6 only!) and store it into a sensor_msgs/PointCloud2. | |
int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version) |
Read a point cloud data from a PCD file and store it into a sensor_msgs/PointCloud2. | |
int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &pcd_version) |
Read a point cloud data header from a PCD file. |
Point Cloud Data (PCD) file format reader.
Definition at line 51 of file pcd_io.h.
anonymous enum |
Various PCD file versions.
PCD_V6 is the entry point for PCL in ROS. It represents PCD files with version .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 .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:
int pcl::PCDReader::read | ( | const std::string & | file_name, | |
pcl::PointCloud< PointT > & | cloud | |||
) | [inline] |
Read a point cloud data from any PCD file, and convert it to the given template format.
file_name | the name of the file containing the actual PointCloud data | |
cloud | the resultant PointCloud message read from disk |
int pcl::PCDReader::read | ( | const std::string & | file_name, | |
sensor_msgs::PointCloud2 & | cloud | |||
) |
Read a point cloud data from a PCD file (PCD_V6 only!) and store it into a sensor_msgs/PointCloud2.
file_name | the name of the file containing the actual PointCloud data | |
cloud | the resultant PointCloud message read from disk |
Definition at line 529 of file pcd_io.cpp.
int pcl::PCDReader::read | ( | const std::string & | file_name, | |
sensor_msgs::PointCloud2 & | cloud, | |||
Eigen::Vector4f & | origin, | |||
Eigen::Quaternionf & | orientation, | |||
int & | pcd_version | |||
) |
Read a point cloud data from a PCD file and store it into a sensor_msgs/PointCloud2.
file_name | the name of the file containing the actual PointCloud data | |
cloud | the resultant PointCloud message read from disk | |
origin | the sensor acquisition origin (only for > PCD_V7 - null if not present) | |
orientation | the sensor acquisition orientation (only for > PCD_V7 - identity if not present) | |
pcd_version | the PCD version of the file (either PCD_V6 or PCD_V7) |
---[ Binary mode only We must re-open the file and read with mmap () for binary
Definition at line 318 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 | |||
) |
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.
Returns: * < 0 (-1) on error * > 0 on success
file_name | the name of the file to load | |
cloud | the resultant point cloud dataset (only the header will be filled) | |
origin | the sensor acquisition origin (only for > PCD_V7 - null if not present) | |
orientation | the sensor acquisition orientation (only for > PCD_V7 - identity if not present) | |
pcd_version | the PCD version of the file (either PCD_V6 or PCD_V7) |
Definition at line 65 of file pcd_io.cpp.