Point Cloud Library (PCL)  1.3.1
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

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)
 Various PLY file versions.
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.

Detailed Description

Point Cloud Data (PLY) file format reader.

Author:
Nizar Sallem

Member Enumeration Documentation

anonymous enum
Enumerator:
PLY_V0 
PLY_V1 

Definition at line 55 of file ply_io.h.


Member Function Documentation

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

Parameters:
stthe string containing the value to convert and copy
cloudthe cloud to copy it to
point_indexthe index of the point
field_idxthe index of the dimension/field
fields_countthe current fields count

Definition at line 144 of file file_io.h.

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:
file_namethe name of the file containing the actual PointCloud data
cloudthe resultant PointCloud message read from disk

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:
file_namethe name of the file containing the actual PointCloud data
cloudthe resultant PointCloud message read from disk

Reimplemented from pcl::FileReader.

Definition at line 104 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:
file_namethe name of the file containing the actual PointCloud data
cloudthe resultant PointCloud message read from disk

Reimplemented from pcl::FileReader.

Definition at line 117 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]

Various PLY file versions.

PLY represents PLY files with. The are organised this way:

  • lines beginning with "comment" are treated as comments
  • ply
  • format [ascii|binary_little_endian|binary_big_endian] 1.0
  • element vertex COUNT
  • [ascii/binary] poinst coordinates

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:
file_namethe name of the file to load
cloudthe resultant point cloud dataset (only the header will be filled)

Implements pcl::FileReader.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines