Point Cloud Library (PCL)  1.3.1
Public Member Functions
pcl::FileReader Class Reference

Point Cloud Data (FILE) file format reader interface. More...

#include <pcl/io/file_io.h>

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

List of all members.

Public Member Functions

 FileReader ()
 empty constructor
virtual ~FileReader ()
 empty destructor
virtual int readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version, int &data_type, int &data_idx)=0
 Read a point cloud data header from a FILE file.
virtual int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &file_version)=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)
 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)
 Read a point cloud data from any FILE 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 (FILE) file format reader interface.

Any (FILE) format file reader should implement its virtual methodes.

Author:
Nizar Sallem

Constructor & Destructor Documentation

pcl::FileReader::FileReader ( ) [inline]

empty constructor

Definition at line 58 of file file_io.h.

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

empty destructor

Definition at line 60 of file file_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]

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.

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

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

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

int pcl::FileReader::read ( const std::string &  file_name,
sensor_msgs::PointCloud2 cloud 
) [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:
file_namethe name of the file containing the actual PointCloud data
cloudthe resultant PointCloud message read from disk

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

Definition at line 105 of file file_io.h.

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

Read a point cloud data from any FILE 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 in pcl::PCDReader, and pcl::PLYReader.

Definition at line 118 of file 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,
int &  data_idx 
) [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:
file_namethe name of the file to load
cloudthe resultant point cloud dataset (only the header will be filled)
originthe sensor acquisition origin (only for > FILE_V7 - null if not present)
orientationthe sensor acquisition orientation (only for > FILE_V7 - identity if not present)
file_versionthe FILE version of the file (either FILE_V6 or FILE_V7)
data_typethe type of data (binary data=1, ascii=0, etc)
data_idxthe offset of cloud data within the file

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


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