Point Cloud Library (PCL)  1.5.1
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Public Types | Public Member Functions
pcl::PLYReader Class Reference

Point Cloud Data (PLY) file format reader. More...

#include <pcl/io/ply_io.h>

Inheritance diagram for pcl::PLYReader:
Inheritance graph
[legend]
Collaboration diagram for pcl::PLYReader:
Collaboration graph
[legend]

List of all members.

Public Types

enum  { PLY_V0 = 0, PLY_V1 = 1 }

Public Member Functions

 PLYReader ()
 ~PLYReader ()
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.

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

Author:
Nizar Sallem

Definition at line 76 of file ply_io.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
PLY_V0 
PLY_V1 

Definition at line 79 of file ply_io.h.


Constructor & Destructor Documentation

Definition at line 85 of file ply_io.h.

Definition at line 92 of file ply_io.h.


Member Function Documentation

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.

Parameters:
[in]file_namethe name of the file containing the actual PointCloud data
[out]cloudthe resultant PointCloud message read from disk
[in]originthe sensor data acquisition origin (translation)
[in]orientationthe sensor data acquisition origin (rotation)
[out]ply_versionthe 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.

Note:
This function is provided for backwards compatibility only and it can only read PLY_V6 files correctly, as sensor_msgs::PointCloud2 does not contain a sensor origin/orientation. Reading any file

PLY_V6 will generate a warning.

Parameters:
[in]file_namethe name of the file containing the actual PointCloud data
[out]cloudthe resultant PointCloud message read from disk

Reimplemented from pcl::FileReader.

Definition at line 137 of file ply_io.h.

template<typename PointT >
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.

Parameters:
[in]file_namethe name of the file containing the actual PointCloud data
[out]cloudthe resultant PointCloud message read from disk

Reimplemented from pcl::FileReader.

Definition at line 150 of file ply_io.h.

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
    Parameters:
    [in]file_namethe name of the file to load
    [out]cloudthe resultant point cloud dataset (only the header will be filled)
    [in]originthe sensor data acquisition origin (translation)
    [in]orientationthe sensor data acquisition origin (rotation)
    [out]ply_versionthe PLY version read from the file
    [out]data_typethe type of PLY data stored in the file
    [out]data_idxthe data index

Implements pcl::FileReader.


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