Public Types | Public Member Functions | Private Member Functions | Private Attributes
pcl::PLYReader Class Reference

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

#include <ply_io.h>

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

List of all members.

Public Types

enum  { PLY_V0 = 0, PLY_V1 = 1 }

Public Member Functions

PLYReaderoperator= (const PLYReader &p)
 PLYReader ()
 PLYReader (const PLYReader &p)
int read (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, 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 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 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, const int offset=0)
 Read a point cloud data from any PLY file, and convert it to the given template format.
int readHeader (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation, int &ply_version, int &data_type, unsigned int &data_idx, const int offset=0)
 Read a point cloud data header from a PLY file.
 ~PLYReader ()

Private Member Functions

void appendFloatProperty (const std::string &name, const size_t &count=1)
void cloudHeightCallback (const int &height)
void cloudWidthCallback (const int &width)
boost::tuple< boost::function
< void()>, boost::function
< void()> > 
elementDefinitionCallback (const std::string &element_name, std::size_t count)
 function called when the keyword element is parsed
bool endHeaderCallback ()
void errorCallback (const std::string &filename, std::size_t line_number, const std::string &message)
 Error callback function.
void infoCallback (const std::string &filename, std::size_t line_number, const std::string &message)
 Info callback function.
template<typename SizeType , typename ScalarType >
boost::tuple< boost::function
< void(SizeType)>
, boost::function< void(ScalarType)>
, boost::function< void()> > 
listPropertyDefinitionCallback (const std::string &element_name, const std::string &property_name)
 function called when a list property is parsed
void objInfoCallback (const std::string &line)
void orientationXaxisXCallback (const float &value)
void orientationXaxisYCallback (const float &value)
void orientationXaxisZCallback (const float &value)
void orientationYaxisXCallback (const float &value)
void orientationYaxisYCallback (const float &value)
void orientationYaxisZCallback (const float &value)
void orientationZaxisXCallback (const float &value)
void orientationZaxisYCallback (const float &value)
void orientationZaxisZCallback (const float &value)
void originXCallback (const float &value)
void originYCallback (const float &value)
void originZCallback (const float &value)
bool parse (const std::string &istream_filename)
void rangeGridBeginCallback ()
void rangeGridEndCallback ()
void rangeGridVertexIndicesBeginCallback (pcl::io::ply::uint8 size)
void rangeGridVertexIndicesElementCallback (pcl::io::ply::int32 vertex_index)
void rangeGridVertexIndicesEndCallback ()
template<typename ScalarType >
boost::function< void(ScalarType)> scalarPropertyDefinitionCallback (const std::string &element_name, const std::string &property_name)
 function called when a scalar property is parsed
void vertexBeginCallback ()
void vertexColorCallback (const std::string &color_name, pcl::io::ply::uint8 color)
void vertexEndCallback ()
void vertexFloatPropertyCallback (pcl::io::ply::float32 value)
void vertexIntensityCallback (pcl::io::ply::uint8 intensity)
void warningCallback (const std::string &filename, std::size_t line_number, const std::string &message)
 Warning callback function.

Private Attributes

sensor_msgs::PointCloud2 * cloud_
Eigen::Matrix3f orientation_
 orientation
Eigen::Vector4f origin_
 origin
::pcl::io::ply::ply_parser parser_
size_t range_count_
std::vector< std::vector< int > > * range_grid_
size_t range_grid_vertex_indices_element_index_
size_t rgb_offset_before_
size_t vertex_count_
int vertex_offset_before_
size_t vertex_properties_counter_

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 77 of file ply_io.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
PLY_V0 
PLY_V1 

Definition at line 80 of file ply_io.h.


Constructor & Destructor Documentation

Definition at line 86 of file ply_io.h.

pcl::PLYReader::PLYReader ( const PLYReader p) [inline]

Definition at line 101 of file ply_io.h.

Definition at line 126 of file ply_io.h.


Member Function Documentation

void pcl::PLYReader::appendFloatProperty ( const std::string &  name,
const size_t &  count = 1 
) [private]

Append a float property to the cloud fields. param[in] name property name param[in] count property count: 1 for scalar properties and higher for a list property.

Definition at line 99 of file ply_io.cpp.

void pcl::PLYReader::cloudHeightCallback ( const int &  height) [inline, private]

Callback function to set the cloud height param[in] height cloud height

Definition at line 381 of file ply_io.h.

void pcl::PLYReader::cloudWidthCallback ( const int &  width) [inline, private]

Callback function to set the cloud width param[in] width cloud width

Definition at line 387 of file ply_io.h.

boost::tuple< boost::function< void()>, boost::function< void()> > pcl::PLYReader::elementDefinitionCallback ( const std::string &  element_name,
std::size_t  count 
) [private]

function called when the keyword element is parsed

Parameters:
[in]element_nameelement name
[in]countnumber of instances

Definition at line 50 of file ply_io.cpp.

Definition at line 92 of file ply_io.cpp.

void pcl::PLYReader::errorCallback ( const std::string &  filename,
std::size_t  line_number,
const std::string &  message 
) [inline, private]

Error callback function.

Parameters:
[in]filenamePLY file read
[in]line_numberline triggering the callback
[in]messageerror message

Definition at line 252 of file ply_io.h.

void pcl::PLYReader::infoCallback ( const std::string &  filename,
std::size_t  line_number,
const std::string &  message 
) [inline, private]

Info callback function.

Parameters:
[in]filenamePLY file read
[in]line_numberline triggering the callback
[in]messageinformation message

Definition at line 230 of file ply_io.h.

boost::tuple< boost::function< void(pcl::io::ply::uint8)>, boost::function< void(pcl::io::ply::int32)>, boost::function< void()> > pcl::PLYReader::listPropertyDefinitionCallback ( const std::string &  element_name,
const std::string &  property_name 
) [private]

function called when a list property is parsed

Parameters:
[in]element_nameelement name to which the property belongs
[in]property_namelist property name

Definition at line 230 of file ply_io.cpp.

void pcl::PLYReader::objInfoCallback ( const std::string &  line) [private]

Callback function for obj_info

Definition at line 331 of file ply_io.cpp.

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

Definition at line 118 of file ply_io.h.

void pcl::PLYReader::orientationXaxisXCallback ( const float &  value) [inline, private]

Callback function for orientation x axis x component. param[in] value orientation x axis x value

Definition at line 327 of file ply_io.h.

void pcl::PLYReader::orientationXaxisYCallback ( const float &  value) [inline, private]

Callback function for orientation x axis y component. param[in] value orientation x axis y value

Definition at line 333 of file ply_io.h.

void pcl::PLYReader::orientationXaxisZCallback ( const float &  value) [inline, private]

Callback function for orientation x axis z component. param[in] value orientation x axis z value

Definition at line 339 of file ply_io.h.

void pcl::PLYReader::orientationYaxisXCallback ( const float &  value) [inline, private]

Callback function for orientation y axis x component. param[in] value orientation y axis x value

Definition at line 345 of file ply_io.h.

void pcl::PLYReader::orientationYaxisYCallback ( const float &  value) [inline, private]

Callback function for orientation y axis y component. param[in] value orientation y axis y value

Definition at line 351 of file ply_io.h.

void pcl::PLYReader::orientationYaxisZCallback ( const float &  value) [inline, private]

Callback function for orientation y axis z component. param[in] value orientation y axis z value

Definition at line 357 of file ply_io.h.

void pcl::PLYReader::orientationZaxisXCallback ( const float &  value) [inline, private]

Callback function for orientation z axis x component. param[in] value orientation z axis x value

Definition at line 363 of file ply_io.h.

void pcl::PLYReader::orientationZaxisYCallback ( const float &  value) [inline, private]

Callback function for orientation z axis y component. param[in] value orientation z axis y value

Definition at line 369 of file ply_io.h.

void pcl::PLYReader::orientationZaxisZCallback ( const float &  value) [inline, private]

Callback function for orientation z axis z component. param[in] value orientation z axis z value

Definition at line 375 of file ply_io.h.

void pcl::PLYReader::originXCallback ( const float &  value) [inline, private]

Callback function for origin x component. param[in] value origin x value

Definition at line 309 of file ply_io.h.

void pcl::PLYReader::originYCallback ( const float &  value) [inline, private]

Callback function for origin y component. param[in] value origin y value

Definition at line 315 of file ply_io.h.

void pcl::PLYReader::originZCallback ( const float &  value) [inline, private]

Callback function for origin z component. param[in] value origin z value

Definition at line 321 of file ply_io.h.

bool pcl::PLYReader::parse ( const std::string &  istream_filename) [private]

Definition at line 354 of file ply_io.cpp.

Callback function for the begin of range_grid line

Definition at line 308 of file ply_io.cpp.

Callback function for the end of a range_grid element end

Definition at line 325 of file ply_io.cpp.

Callback function for the begin of range_grid vertex_indices property param[in] size vertex_indices list size

Definition at line 311 of file ply_io.cpp.

Callback function for each range_grid vertex_indices element param[in] vertex_index index of the vertex in vertex_indices

Definition at line 316 of file ply_io.cpp.

Callback function for the end of a range_grid vertex_indices property

Definition at line 322 of file ply_io.cpp.

int pcl::PLYReader::read ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation,
int &  ply_version,
const int  offset = 0 
) [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
[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).

Implements pcl::FileReader.

Definition at line 399 of file ply_io.cpp.

int pcl::PLYReader::read ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
const int  offset = 0 
) [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
[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 from pcl::FileReader.

Definition at line 186 of file ply_io.h.

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_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 from pcl::FileReader.

Definition at line 204 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,
unsigned int &  data_idx,
const int  offset = 0 
) [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
[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).

Implements pcl::FileReader.

Definition at line 381 of file ply_io.cpp.

boost::function< void(pcl::io::ply::int32)> pcl::PLYReader::scalarPropertyDefinitionCallback ( const std::string &  element_name,
const std::string &  property_name 
) [private]

function called when a scalar property is parsed

Parameters:
[in]element_nameelement name to which the property belongs
[in]property_nameproperty name

Definition at line 114 of file ply_io.cpp.

Callback function for the begin of vertex line

Definition at line 296 of file ply_io.cpp.

void pcl::PLYReader::vertexColorCallback ( const std::string &  color_name,
pcl::io::ply::uint8  color 
) [inline, private]

Callback function for vertex RGB color. This callback is in charge of packing red green and blue in a single int before writing it down in cloud data. param[in] color_name color name in {red, green, blue} param[in] color value of {red, green, blue} property

Definition at line 262 of file ply_io.cpp.

Callback function for the end of vertex line

Definition at line 302 of file ply_io.cpp.

Callback function for an anonymous vertex float property. Writes down a float value in cloud data. param[in] value float value parsed

Definition at line 253 of file ply_io.cpp.

void pcl::PLYReader::vertexIntensityCallback ( pcl::io::ply::uint8  intensity) [inline, private]

Callback function for vertex intensity. converts intensity from int to float before writing it down in cloud data. param[in] intensity

Definition at line 286 of file ply_io.cpp.

void pcl::PLYReader::warningCallback ( const std::string &  filename,
std::size_t  line_number,
const std::string &  message 
) [inline, private]

Warning callback function.

Parameters:
[in]filenamePLY file read
[in]line_numberline triggering the callback
[in]messagewarning message

Definition at line 241 of file ply_io.h.


Member Data Documentation

sensor_msgs::PointCloud2* pcl::PLYReader::cloud_ [private]

Definition at line 440 of file ply_io.h.

Eigen::Matrix3f pcl::PLYReader::orientation_ [private]

orientation

Definition at line 437 of file ply_io.h.

Eigen::Vector4f pcl::PLYReader::origin_ [private]

origin

Definition at line 434 of file ply_io.h.

Definition at line 219 of file ply_io.h.

size_t pcl::PLYReader::range_count_ [private]

Definition at line 445 of file ply_io.h.

std::vector<std::vector <int> >* pcl::PLYReader::range_grid_ [private]

Definition at line 444 of file ply_io.h.

Definition at line 445 of file ply_io.h.

Definition at line 446 of file ply_io.h.

Definition at line 441 of file ply_io.h.

Definition at line 442 of file ply_io.h.

Definition at line 441 of file ply_io.h.


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


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