|
Point Cloud Library (PCL)
1.4.0
|
Point Cloud Data (PLY) file format reader. More...
#include <pcl/io/ply_io.h>


Public Types | |
| enum | { PLY_V0 = 0, PLY_V1 = 1 } |
Public Member Functions | |
| int | readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, int &data_type, int &data_idx) |
| Read a point cloud data header from a PLY file. | |
| int | read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version) |
| Read a point cloud data from a PLY 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 PLY file (PLY_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 PLY file, and convert it to the given template format. | |
| template<typename Type > | |
| void | copyStringValue (const std::string &st, sensor_msgs::PointCloud2 &cloud, unsigned int point_index, unsigned int field_idx, unsigned int fields_count) |
| Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string. | |
Point Cloud Data (PLY) file format reader.
The PLY data format is organized in the following way:
| void pcl::FileReader::copyStringValue | ( | const std::string & | st, |
| sensor_msgs::PointCloud2 & | cloud, | ||
| unsigned int | point_index, | ||
| unsigned int | field_idx, | ||
| unsigned int | fields_count | ||
| ) | [inline, inherited] |
Copy one single value of type T (uchar, char, uint, int, float, double, ...) from a string.
Uses aoti/atof to do the conversion. Checks if the st is "nan" and converts it accordingly.
| [in] | st | the string containing the value to convert and copy |
| [out] | cloud | the cloud to copy it to |
| [in] | point_index | the index of the point |
| [in] | field_idx | the index of the dimension/field |
| [in] | fields_count | the current fields count |
| int pcl::PLYReader::read | ( | const std::string & | file_name, |
| sensor_msgs::PointCloud2 & | cloud, | ||
| Eigen::Vector4f & | origin, | ||
| Eigen::Quaternionf & | orientation, | ||
| int & | ply_version | ||
| ) | [virtual] |
Read a point cloud data from a PLY 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 |
| [in] | origin | the sensor data acquisition origin (translation) |
| [in] | orientation | the sensor data acquisition origin (rotation) |
| [out] | ply_version | the PLY version read from the file |
Implements pcl::FileReader.
| int pcl::PLYReader::read | ( | const std::string & | file_name, |
| sensor_msgs::PointCloud2 & | cloud | ||
| ) | [inline] |
Read a point cloud data from a PLY file (PLY_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 |
Reimplemented from pcl::FileReader.
| int pcl::PLYReader::read | ( | const std::string & | file_name, |
| pcl::PointCloud< PointT > & | cloud | ||
| ) | [inline] |
Read a point cloud data from any PLY 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 from pcl::FileReader.
| int pcl::PLYReader::readHeader | ( | const std::string & | file_name, |
| sensor_msgs::PointCloud2 & | cloud, | ||
| Eigen::Vector4f & | origin, | ||
| Eigen::Quaternionf & | orientation, | ||
| int & | ply_version, | ||
| int & | data_type, | ||
| int & | data_idx | ||
| ) | [virtual] |
Read a point cloud data header from a PLY file.
Load only the meta information (number of points, their types, etc), and not the points themselves, from a given PLY 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) |
| [in] | origin | the sensor data acquisition origin (translation) |
| [in] | orientation | the sensor data acquisition origin (rotation) |
| [out] | ply_version | the PLY version read from the file |
| [out] | data_type | the type of PLY data stored in the file |
| [out] | data_idx | the data index |
Implements pcl::FileReader.
1.7.6.1