Public Member Functions
pcl::FileReader Class Reference

Point Cloud Data (FILE) file format reader interface. Any (FILE) format file reader should implement its virtual methodes. More...

#include <file_io.h>

Inheritance diagram for pcl::FileReader:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 FileReader ()
 empty constructor
virtual int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, const int offset=0)=0
 Read a point cloud data from a FILE file and store it into a sensor_msgs/PointCloud2.
int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, const int offset=0)
 Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a sensor_msgs/PointCloud2.
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.
virtual int readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, int &data_type, unsigned int &data_idx, const int offset=0)=0
 Read a point cloud data header from a FILE file.
virtual ~FileReader ()
 empty destructor

Detailed Description

Point Cloud Data (FILE) file format reader interface. Any (FILE) format file reader should implement its virtual methodes.

Author:
Nizar Sallem

Definition at line 54 of file io/include/pcl/io/file_io.h.


Constructor & Destructor Documentation

empty constructor

Definition at line 58 of file io/include/pcl/io/file_io.h.

virtual pcl::FileReader::~FileReader ( ) [inline, virtual]

empty destructor

Definition at line 60 of file io/include/pcl/io/file_io.h.


Member Function Documentation

virtual int pcl::FileReader::read ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation,
int &  file_version,
const int  offset = 0 
) [pure virtual]

Read a point cloud data from a FILE 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
[out]originthe sensor acquisition origin (only for > FILE_V7 - null if not present)
[out]orientationthe sensor acquisition orientation (only for > FILE_V7 - identity if not present)
[out]file_versionthe FILE version of the file (either FILE_V6 or FILE_V7)
[in]offsetthe 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).

Implemented in pcl::PCDReader, and pcl::PLYReader.

int pcl::FileReader::read ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
const int  offset = 0 
) [inline]

Read a point cloud data from a FILE file (FILE_V6 only!) and store it into a sensor_msgs/PointCloud2.

Note:
This function is provided for backwards compatibility only and it can only read FILE_V6 files correctly, as sensor_msgs::PointCloud2 does not contain a sensor origin/orientation. Reading any file > FILE_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
[in]offsetthe 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).

Reimplemented in pcl::PCDReader, and pcl::PLYReader.

Definition at line 122 of file io/include/pcl/io/file_io.h.

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

Read a point cloud data from any FILE 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
[in]offsetthe 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).

Reimplemented in pcl::PCDReader, and pcl::PLYReader.

Definition at line 140 of file io/include/pcl/io/file_io.h.

virtual int pcl::FileReader::readHeader ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation,
int &  file_version,
int &  data_type,
unsigned int &  data_idx,
const int  offset = 0 
) [pure virtual]

Read a point cloud data header from a FILE file.

Load only the meta information (number of points, their types, etc), and not the points themselves, from a given FILE 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)
[out]originthe sensor acquisition origin (only for > FILE_V7 - null if not present)
[out]orientationthe sensor acquisition orientation (only for > FILE_V7 - identity if not present)
[out]file_versionthe FILE version of the file (either FILE_V6 or FILE_V7)
[out]data_typethe type of data (binary data=1, ascii=0, etc)
[out]data_idxthe offset of cloud data within the file
[in]offsetthe 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).

Implemented in pcl::PLYReader, and pcl::PCDReader.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:28