Point Cloud Data (PLY) file format reader. More...
#include <ply_io.h>
Public Types | |
enum | { PLY_V0 = 0, PLY_V1 = 1 } |
Public Member Functions | |
PLYReader & | operator= (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_ |
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
pcl::PLYReader::PLYReader | ( | ) | [inline] |
pcl::PLYReader::PLYReader | ( | const PLYReader & | p | ) | [inline] |
pcl::PLYReader::~PLYReader | ( | ) | [inline] |
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] |
void pcl::PLYReader::cloudWidthCallback | ( | const int & | width | ) | [inline, private] |
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
[in] | element_name | element name |
[in] | count | number of instances |
Definition at line 50 of file ply_io.cpp.
bool pcl::PLYReader::endHeaderCallback | ( | ) | [private] |
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] |
void pcl::PLYReader::infoCallback | ( | const std::string & | filename, |
std::size_t | line_number, | ||
const std::string & | message | ||
) | [inline, private] |
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
[in] | element_name | element name to which the property belongs |
[in] | property_name | list 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.
void pcl::PLYReader::orientationXaxisXCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationXaxisYCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationXaxisZCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationYaxisXCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationYaxisYCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationYaxisZCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationZaxisXCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationZaxisYCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::orientationZaxisZCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::originXCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::originYCallback | ( | const float & | value | ) | [inline, private] |
void pcl::PLYReader::originZCallback | ( | const float & | value | ) | [inline, private] |
bool pcl::PLYReader::parse | ( | const std::string & | istream_filename | ) | [private] |
Definition at line 354 of file ply_io.cpp.
void pcl::PLYReader::rangeGridBeginCallback | ( | ) | [private] |
Callback function for the begin of range_grid line
Definition at line 308 of file ply_io.cpp.
void pcl::PLYReader::rangeGridEndCallback | ( | ) | [private] |
Callback function for the end of a range_grid element end
Definition at line 325 of file ply_io.cpp.
void pcl::PLYReader::rangeGridVertexIndicesBeginCallback | ( | pcl::io::ply::uint8 | size | ) | [private] |
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.
void pcl::PLYReader::rangeGridVertexIndicesElementCallback | ( | pcl::io::ply::int32 | vertex_index | ) | [private] |
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.
void pcl::PLYReader::rangeGridVertexIndicesEndCallback | ( | ) | [private] |
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.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
[out] | ply_version | the PLY version read from the file |
[in] | offset | the 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.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[in] | offset | the 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.
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.
[in] | file_name | the name of the file containing the actual PointCloud data |
[out] | cloud | the resultant PointCloud message read from disk |
[in] | offset | the 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.
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
[in] | file_name | the name of the file to load |
[out] | cloud | the resultant point cloud dataset (only the header will be filled) |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
[out] | ply_version | the PLY version read from the file |
[out] | data_type | the type of PLY data stored in the file |
[out] | data_idx | the data index |
[in] | offset | the 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
[in] | element_name | element name to which the property belongs |
[in] | property_name | property name |
Definition at line 114 of file ply_io.cpp.
void pcl::PLYReader::vertexBeginCallback | ( | ) | [private] |
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.
void pcl::PLYReader::vertexEndCallback | ( | ) | [private] |
Callback function for the end of vertex line
Definition at line 302 of file ply_io.cpp.
void pcl::PLYReader::vertexFloatPropertyCallback | ( | pcl::io::ply::float32 | value | ) | [inline, private] |
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] |
sensor_msgs::PointCloud2* pcl::PLYReader::cloud_ [private] |
Eigen::Matrix3f pcl::PLYReader::orientation_ [private] |
Eigen::Vector4f pcl::PLYReader::origin_ [private] |
::pcl::io::ply::ply_parser pcl::PLYReader::parser_ [private] |
size_t pcl::PLYReader::range_count_ [private] |
std::vector<std::vector <int> >* pcl::PLYReader::range_grid_ [private] |
size_t pcl::PLYReader::range_grid_vertex_indices_element_index_ [private] |
size_t pcl::PLYReader::rgb_offset_before_ [private] |
size_t pcl::PLYReader::vertex_count_ [private] |
int pcl::PLYReader::vertex_offset_before_ [private] |
size_t pcl::PLYReader::vertex_properties_counter_ [private] |