point_cloud_library / 1.12.1 / classpcl_1_1_p_l_y_reader.html /

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

PLYReader ()
PLYReader (const PLYReader &p)
PLYReader & operator= (const PLYReader &p)
~PLYReader ()
int readHeader (const std::string &file_name, pcl::PCLPointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, int &data_type, unsigned int &data_idx, const int offset=0) override
Read a point cloud data header from a PLY file. More...
int read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, const int offset=0) override
Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2. More...
int read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2. More...
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 PLY file, and convert it to the given template format. More...
int read (const std::string &file_name, pcl::PolygonMesh &mesh, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh. More...
int read (const std::string &file_name, pcl::PolygonMesh &mesh, const int offset=0)
Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh. More...
- Public Member Functions inherited from pcl::FileReader
FileReader ()
empty constructor More...
virtual ~FileReader ()
empty destructor More...
int read (const std::string &file_name, pcl::PCLPointCloud2 &cloud, const int offset=0)
Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a pcl/PCLPointCloud2. More...
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. More...

Detailed Description

Point Cloud Data (PLY) file format reader.

The PLY data format is organized in the following way: lines beginning with "comment" are treated as comments

  • ply
  • format [ascii|binary_little_endian|binary_big_endian] 1.0
  • element vertex COUNT
  • property float x
  • property float y
  • [property float z]
  • [property float normal_x]
  • [property float normal_y]
  • [property float normal_z]
  • [property uchar red]
  • [property uchar green]
  • [property uchar blue] ...
  • ascii/binary point coordinates
  • [element camera 1]
  • [property float view_px] ...
  • [element range_grid COUNT]
  • [property list uchar int vertex_indices]
  • end header
Author
Nizar Sallem

Definition at line 79 of file ply_io.h.

Member Enumeration Documentation

anonymous enum

anonymous enum
Enumerator
PLY_V0
PLY_V1

Definition at line 82 of file ply_io.h.

Constructor & Destructor Documentation

PLYReader() [1/2]

pcl::PLYReader::PLYReader ( )
inline

Definition at line 88 of file ply_io.h.

PLYReader() [2/2]

pcl::PLYReader::PLYReader ( const PLYReader & p )
inline

Definition at line 102 of file ply_io.h.

~PLYReader()

pcl::PLYReader::~PLYReader ( )
inline

Definition at line 128 of file ply_io.h.

Member Function Documentation

operator=()

PLYReader& pcl::PLYReader::operator= ( const PLYReader & p )
inline

Definition at line 119 of file ply_io.h.

read() [1/5]

int pcl::PLYReader::read ( const std::string & file_name,
pcl::PCLPointCloud2 & cloud,
const int offset = 0
)
inline

Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.

Note
This function is provided for backwards compatibility only
Parameters
[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).

Definition at line 183 of file ply_io.h.

References pcl::read().

read() [2/5]

int pcl::PLYReader::read ( const std::string & file_name,
pcl::PCLPointCloud2 & cloud,
Eigen::Vector4f & origin,
Eigen::Quaternionf & orientation,
int & ply_version,
const int offset = 0
)
overridevirtual

Read a point cloud data from a PLY file and store it into a pcl/PCLPointCloud2.

Parameters
[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
[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).

Implements pcl::FileReader.

Referenced by pcl::io::loadPLYFile().

read() [3/5]

template<typename PointT >
int pcl::PLYReader::read ( const std::string & file_name,
pcl::PointCloud< PointT > & cloud,
const int offset = 0
)
inline

Read a point cloud data from any PLY file, and convert it to the given template format.

Parameters
[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).

Definition at line 201 of file ply_io.h.

References pcl::fromPCLPointCloud2(), pcl::read(), pcl::PointCloud< PointT >::sensor_orientation_, and pcl::PointCloud< PointT >::sensor_origin_.

read() [4/5]

int pcl::PLYReader::read ( const std::string & file_name,
pcl::PolygonMesh & mesh,
const int offset = 0
)

Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.

Parameters
[in] file_name the name of the file containing the actual PointCloud data
[out] mesh the resultant PolygonMesh 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).

read() [5/5]

int pcl::PLYReader::read ( const std::string & file_name,
pcl::PolygonMesh & mesh,
Eigen::Vector4f & origin,
Eigen::Quaternionf & orientation,
int & ply_version,
const int offset = 0
)

Read a point cloud data from a PLY file and store it into a pcl/PolygonMesh.

Parameters
[in] file_name the name of the file containing the actual PointCloud data
[out] mesh the resultant PolygonMesh 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
[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).

readHeader()

int pcl::PLYReader::readHeader ( const std::string & file_name,
pcl::PCLPointCloud2 & cloud,
Eigen::Vector4f & origin,
Eigen::Quaternionf & orientation,
int & ply_version,
int & data_type,
unsigned int & data_idx,
const int offset = 0
)
overridevirtual

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
    Parameters
    [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
    [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).

Implements pcl::FileReader.


The documentation for this class was generated from the following file:

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1_p_l_y_reader.html