Namespaces | Classes | Functions
pcl::io Namespace Reference

Namespaces

namespace  ply

Classes

struct  TARHeader
 A TAR file's header, as described on http://en.wikipedia.org/wiki/Tar_%28file_format%29. More...

Functions

int loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 Load a PCD v.6 file into a templated PointCloud type.
int loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
 Load any PCD file into a templated PointCloud type.
template<typename PointT >
int loadPCDFile (const std::string &file_name, pcl::PointCloud< PointT > &cloud)
 Load any PCD file into a templated PointCloud type.
int loadPLYFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 Load a PLY v.6 file into a templated PointCloud type.
int loadPLYFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud, Eigen::Vector4f &origin, Eigen::Quaternionf &orientation)
 Load any PLY file into a templated PointCloud type.
template<typename PointT >
int loadPLYFile (const std::string &file_name, pcl::PointCloud< PointT > &cloud)
 Load any PLY file into a templated PointCloud type.
PCL_EXPORTS int loadPolygonFile (const std::string &file_name, pcl::PolygonMesh &mesh)
 Load a PolygonMesh object given an input file name, based on the file extension.
PCL_EXPORTS int loadPolygonFileOBJ (const std::string &file_name, pcl::PolygonMesh &mesh)
 Load an OBJ file into a PolygonMesh object.
PCL_EXPORTS int loadPolygonFilePLY (const std::string &file_name, pcl::PolygonMesh &mesh)
 Load a PLY file into a PolygonMesh object.
PCL_EXPORTS int loadPolygonFileSTL (const std::string &file_name, pcl::PolygonMesh &mesh)
 Load an STL file into a PolygonMesh object.
PCL_EXPORTS int loadPolygonFileVTK (const std::string &file_name, pcl::PolygonMesh &mesh)
 Load a VTK file into a PolygonMesh object.
PCL_EXPORTS int mesh2vtk (const pcl::PolygonMesh &mesh, vtkSmartPointer< vtkPolyData > &poly_data)
 Convert a PCL PolygonMesh to a vtkPolyData object.
template<typename PointT >
void pointCloudTovtkPolyData (const pcl::PointCloud< PointT > &cloud, vtkPolyData *const polydata)
 Convert a pcl::PointCloud object to a VTK PolyData one.
template<typename PointT >
void pointCloudTovtkStructuredGrid (const pcl::PointCloud< PointT > &cloud, vtkStructuredGrid *const structured_grid)
 Convert a pcl::PointCloud object to a VTK StructuredGrid one.
PCL_EXPORTS int saveOBJFile (const std::string &file_name, const pcl::TextureMesh &tex_mesh, unsigned precision=5)
 Saves a TextureMesh in ascii OBJ format.
PCL_EXPORTS int saveOBJFile (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision=5)
 Saves a PolygonMesh in ascii PLY format.
int savePCDFile (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary_mode=false)
 Save point cloud data to a PCD file containing n-D points.
template<typename PointT >
int savePCDFile (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, bool binary_mode=false)
 Templated version for saving point cloud data to a PCD file containing a specific given cloud format.
template<typename PointT >
int savePCDFile (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const bool binary_mode=false)
 Templated version for saving point cloud data to a PCD file containing a specific given cloud format.
template<typename PointT >
int savePCDFileASCII (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Templated version for saving point cloud data to a PCD file containing a specific given cloud format.
template<typename PointT >
int savePCDFileBinary (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Templated version for saving point cloud data to a PCD file containing a specific given cloud format.
int savePLYFile (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), bool binary_mode=false, bool use_camera=true)
 Save point cloud data to a PLY file containing n-D points.
template<typename PointT >
int savePLYFile (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, bool binary_mode=false)
 Templated version for saving point cloud data to a PLY file containing a specific given cloud format.
template<typename PointT >
int savePLYFile (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, bool binary_mode=false)
 Templated version for saving point cloud data to a PLY file containing a specific given cloud format.
PCL_EXPORTS int savePLYFile (const std::string &file_name, const pcl::PolygonMesh &mesh, unsigned precision=5)
 Saves a PolygonMesh in ascii PLY format.
template<typename PointT >
int savePLYFileASCII (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Templated version for saving point cloud data to a PLY file containing a specific given cloud format.
template<typename PointT >
int savePLYFileBinary (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Templated version for saving point cloud data to a PLY file containing a specific given cloud format.
PCL_EXPORTS int savePolygonFile (const std::string &file_name, const pcl::PolygonMesh &mesh)
 Save a PolygonMesh object given an input file name, based on the file extension.
PCL_EXPORTS int savePolygonFilePLY (const std::string &file_name, const pcl::PolygonMesh &mesh)
 Save a PolygonMesh object into a PLY file.
PCL_EXPORTS int savePolygonFileSTL (const std::string &file_name, const pcl::PolygonMesh &mesh)
 Save a PolygonMesh object into an STL file.
PCL_EXPORTS int savePolygonFileVTK (const std::string &file_name, const pcl::PolygonMesh &mesh)
 Save a PolygonMesh object into a VTK file.
PCL_EXPORTS void saveRangeImagePlanarFilePNG (const std::string &file_name, const pcl::RangeImagePlanar &range_image)
 Write a RangeImagePlanar object to a PNG file.
PCL_EXPORTS int saveVTKFile (const std::string &file_name, const pcl::PolygonMesh &triangles, unsigned precision=5)
 Saves a PolygonMesh in ascii VTK format.
PCL_EXPORTS int saveVTKFile (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, unsigned precision=5)
 Saves a PointCloud in ascii VTK format.
template<std::size_t N>
void swapByte (char *bytes)
 swap bytes order of a char array of length N
template<typename T >
void swapByte (T &value)
 swaps byte of an arbitrary type T casting it to char*
template<>
void swapByte< 1 > (char *bytes)
 specialization of swapByte for dimension 1
template<>
void swapByte< 2 > (char *bytes)
 specialization of swapByte for dimension 2
template<>
void swapByte< 4 > (char *bytes)
 specialization of swapByte for dimension 4
template<>
void swapByte< 8 > (char *bytes)
 specialization of swapByte for dimension 8
PCL_EXPORTS int vtk2mesh (const vtkSmartPointer< vtkPolyData > &poly_data, pcl::PolygonMesh &mesh)
 Convert vtkPolyData object to a PCL PolygonMesh.
template<typename PointT >
void vtkPolyDataToPointCloud (vtkPolyData *const polydata, pcl::PointCloud< PointT > &cloud)
 Convert a VTK PolyData object to a pcl::PointCloud one.
template<typename PointT >
void vtkStructuredGridToPointCloud (vtkStructuredGrid *const structured_grid, pcl::PointCloud< PointT > &cloud)
 Convert a VTK StructuredGrid object to a pcl::PointCloud one.

Function Documentation

int pcl::io::loadPCDFile ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud 
) [inline]

Load a PCD v.6 file into a templated PointCloud type.

Any PCD files > v.6 will generate a warning as a sensor_msgs/PointCloud2 message cannot hold the sensor origin.

Parameters:
[in]file_namethe name of the file to load
[out]cloudthe resultant templated point cloud

Definition at line 606 of file pcd_io.h.

int pcl::io::loadPCDFile ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation 
) [inline]

Load any PCD file into a templated PointCloud type.

Parameters:
[in]file_namethe name of the file to load
[out]cloudthe resultant templated point cloud
[out]originthe sensor acquisition origin (only for > PCD_V7 - null if not present)
[out]orientationthe sensor acquisition orientation (only for > PCD_V7 - identity if not present)

Definition at line 621 of file pcd_io.h.

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

Load any PCD file into a templated PointCloud type.

Parameters:
[in]file_namethe name of the file to load
[out]cloudthe resultant templated point cloud

Definition at line 635 of file pcd_io.h.

int pcl::io::loadPLYFile ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud 
) [inline]

Load a PLY v.6 file into a templated PointCloud type.

Any PLY files containg sensor data will generate a warning as a sensor_msgs/PointCloud2 message cannot hold the sensor origin.

Parameters:
[in]file_namethe name of the file to load
[in]cloudthe resultant templated point cloud

Definition at line 658 of file ply_io.h.

int pcl::io::loadPLYFile ( const std::string &  file_name,
sensor_msgs::PointCloud2 &  cloud,
Eigen::Vector4f &  origin,
Eigen::Quaternionf &  orientation 
) [inline]

Load any PLY file into a templated PointCloud type.

Parameters:
[in]file_namethe name of the file to load
[in]cloudthe resultant templated point cloud
[in]originthe sensor acquisition origin (only for > PLY_V7 - null if not present)
[in]orientationthe sensor acquisition orientation if availble, identity if not present

Definition at line 673 of file ply_io.h.

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

Load any PLY file into a templated PointCloud type.

Parameters:
[in]file_namethe name of the file to load
[in]cloudthe resultant templated point cloud

Definition at line 687 of file ply_io.h.

int pcl::io::loadPolygonFile ( const std::string &  file_name,
pcl::PolygonMesh &  mesh 
)

Load a PolygonMesh object given an input file name, based on the file extension.

Parameters:
[in]file_namethe name of the file containing the polygon data
[out]meshthe object that we want to load the data in

Definition at line 46 of file vtk_lib_io.cpp.

int pcl::io::loadPolygonFileOBJ ( const std::string &  file_name,
pcl::PolygonMesh &  mesh 
)

Load an OBJ file into a PolygonMesh object.

Parameters:
[in]file_namethe name of the file that contains the data
[out]meshthe object that we want to load the data in

Definition at line 137 of file vtk_lib_io.cpp.

int pcl::io::loadPolygonFilePLY ( const std::string &  file_name,
pcl::PolygonMesh &  mesh 
)

Load a PLY file into a PolygonMesh object.

Parameters:
[in]file_namethe name of the file that contains the data
[out]meshthe object that we want to load the data in

Definition at line 123 of file vtk_lib_io.cpp.

int pcl::io::loadPolygonFileSTL ( const std::string &  file_name,
pcl::PolygonMesh &  mesh 
)

Load an STL file into a PolygonMesh object.

Parameters:
[in]file_namethe name of the file that contains the data
[out]meshthe object that we want to load the data in

Definition at line 150 of file vtk_lib_io.cpp.

int pcl::io::loadPolygonFileVTK ( const std::string &  file_name,
pcl::PolygonMesh &  mesh 
)

Load a VTK file into a PolygonMesh object.

Parameters:
[in]file_namethe name of the file that contains the data
[out]meshthe object that we want to load the data in

Definition at line 109 of file vtk_lib_io.cpp.

int pcl::io::mesh2vtk ( const pcl::PolygonMesh &  mesh,
vtkSmartPointer< vtkPolyData > &  poly_data 
)

Convert a PCL PolygonMesh to a vtkPolyData object.

Parameters:
[in]meshReference to PCL Polygon Mesh
[out]poly_dataPointer (vtkSmartPointer) to a vtkPolyData object
Returns:
Number of points in the point cloud of mesh.

Definition at line 301 of file vtk_lib_io.cpp.

template<typename PointT >
void pcl::io::pointCloudTovtkPolyData ( const pcl::PointCloud< PointT > &  cloud,
vtkPolyData *const  polydata 
)

Convert a pcl::PointCloud object to a VTK PolyData one.

Parameters:
[in]cloudthe input pcl::PointCloud object
[out]polydatathe resultant VTK PolyData object

Definition at line 277 of file vtk_lib_io.hpp.

template<typename PointT >
void pcl::io::pointCloudTovtkStructuredGrid ( const pcl::PointCloud< PointT > &  cloud,
vtkStructuredGrid *const  structured_grid 
)

Convert a pcl::PointCloud object to a VTK StructuredGrid one.

Parameters:
[in]cloudthe input pcl::PointCloud object
[out]structured_gridthe resultant VTK StructuredGrid object

Definition at line 364 of file vtk_lib_io.hpp.

int pcl::io::saveOBJFile ( const std::string &  file_name,
const pcl::TextureMesh tex_mesh,
unsigned  precision = 5 
)

Saves a TextureMesh in ascii OBJ format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]tex_meshthe texture mesh to save
[in]precisionthe output ASCII precision

Definition at line 45 of file obj_io.cpp.

int pcl::io::saveOBJFile ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh,
unsigned  precision = 5 
)

Saves a PolygonMesh in ascii PLY format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]meshthe polygonal mesh to save
[in]precisionthe output ASCII precision default 5

Definition at line 242 of file obj_io.cpp.

int pcl::io::savePCDFile ( const std::string &  file_name,
const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin = Eigen::Vector4f::Zero (),
const Eigen::Quaternionf &  orientation = Eigen::Quaternionf::Identity (),
const bool  binary_mode = false 
) [inline]

Save point cloud data to a PCD file containing n-D points.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation
[in]binary_modetrue for binary mode, false (default) for ASCII

Caution: PointCloud structures containing an RGB field have traditionally used packed float values to store RGB data. Storing a float as ASCII can introduce variations to the smallest bits, and thus significantly alter the data. This is a known issue, and the fix involves switching RGB data to be stored as a packed integer in future versions of PCL.

Definition at line 657 of file pcd_io.h.

template<typename PointT >
int pcl::io::savePCDFile ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
bool  binary_mode = false 
) [inline]

Templated version for saving point cloud data to a PCD file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]binary_modetrue for binary mode, false (default) for ASCII

Caution: PointCloud structures containing an RGB field have traditionally used packed float values to store RGB data. Storing a float as ASCII can introduce variations to the smallest bits, and thus significantly alter the data. This is a known issue, and the fix involves switching RGB data to be stored as a packed integer in future versions of PCL.

Definition at line 681 of file pcd_io.h.

template<typename PointT >
int pcl::io::savePCDFile ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const std::vector< int > &  indices,
const bool  binary_mode = false 
)

Templated version for saving point cloud data to a PCD file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]indicesthe set of indices to save
[in]binary_modetrue for binary mode, false (default) for ASCII

Caution: PointCloud structures containing an RGB field have traditionally used packed float values to store RGB data. Storing a float as ASCII can introduce variations to the smallest bits, and thus significantly alter the data. This is a known issue, and the fix involves switching RGB data to be stored as a packed integer in future versions of PCL.

Definition at line 744 of file pcd_io.h.

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

Templated version for saving point cloud data to a PCD file containing a specific given cloud format.

This version is to retain backwards compatibility.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message

Caution: PointCloud structures containing an RGB field have traditionally used packed float values to store RGB data. Storing a float as ASCII can introduce variations to the smallest bits, and thus significantly alter the data. This is a known issue, and the fix involves switching RGB data to be stored as a packed integer in future versions of PCL.

Definition at line 704 of file pcd_io.h.

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

Templated version for saving point cloud data to a PCD file containing a specific given cloud format.

This version is to retain backwards compatibility.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message

Definition at line 720 of file pcd_io.h.

int pcl::io::savePLYFile ( const std::string &  file_name,
const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin = Eigen::Vector4f::Zero (),
const Eigen::Quaternionf &  orientation = Eigen::Quaternionf::Identity (),
bool  binary_mode = false,
bool  use_camera = true 
) [inline]

Save point cloud data to a PLY file containing n-D points.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]originthe sensor data acquisition origin (translation)
[in]orientationthe sensor data acquisition origin (rotation)
[in]binary_modetrue for binary mode, false (default) for ASCII

Definition at line 702 of file ply_io.h.

template<typename PointT >
int pcl::io::savePLYFile ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
bool  binary_mode = false 
) [inline]

Templated version for saving point cloud data to a PLY file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]binary_modetrue for binary mode, false (default) for ASCII

Definition at line 719 of file ply_io.h.

template<typename PointT >
int pcl::io::savePLYFile ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const std::vector< int > &  indices,
bool  binary_mode = false 
)

Templated version for saving point cloud data to a PLY file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]indicesthe set of indices to save
[in]binary_modetrue for binary mode, false (default) for ASCII

Definition at line 758 of file ply_io.h.

int pcl::io::savePLYFile ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh,
unsigned  precision = 5 
)

Saves a PolygonMesh in ascii PLY format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]meshthe polygonal mesh to save
[in]precisionthe output ASCII precision default 5

Definition at line 1151 of file ply_io.cpp.

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

Templated version for saving point cloud data to a PLY file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message

Definition at line 732 of file ply_io.h.

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

Templated version for saving point cloud data to a PLY file containing a specific given cloud format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message

Definition at line 744 of file ply_io.h.

int pcl::io::savePolygonFile ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh 
)

Save a PolygonMesh object given an input file name, based on the file extension.

Parameters:
[in]file_namethe name of the file to save the data to
[in]meshthe object that contains the data

Definition at line 79 of file vtk_lib_io.cpp.

int pcl::io::savePolygonFilePLY ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh 
)

Save a PolygonMesh object into a PLY file.

Parameters:
[in]file_namethe name of the file to save the data to
[in]meshthe object that contains the data

Definition at line 180 of file vtk_lib_io.cpp.

int pcl::io::savePolygonFileSTL ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh 
)

Save a PolygonMesh object into an STL file.

Parameters:
[in]file_namethe name of the file to save the data to
[in]meshthe object that contains the data

Definition at line 197 of file vtk_lib_io.cpp.

int pcl::io::savePolygonFileVTK ( const std::string &  file_name,
const pcl::PolygonMesh &  mesh 
)

Save a PolygonMesh object into a VTK file.

Parameters:
[in]file_namethe name of the file to save the data to
[in]meshthe object that contains the data

Definition at line 164 of file vtk_lib_io.cpp.

void pcl::io::saveRangeImagePlanarFilePNG ( const std::string &  file_name,
const pcl::RangeImagePlanar range_image 
)

Write a RangeImagePlanar object to a PNG file.

Parameters:
[in]file_namethe name of the file to save the data to
[in]range_imagethe object that contains the data

Definition at line 397 of file vtk_lib_io.cpp.

int pcl::io::saveVTKFile ( const std::string &  file_name,
const pcl::PolygonMesh &  triangles,
unsigned  precision = 5 
)

Saves a PolygonMesh in ascii VTK format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]trianglesthe polygonal mesh to save
[in]precisionthe output ASCII precision

Definition at line 48 of file vtk_io.cpp.

int pcl::io::saveVTKFile ( const std::string &  file_name,
const sensor_msgs::PointCloud2 &  cloud,
unsigned  precision = 5 
)

Saves a PointCloud in ascii VTK format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]cloudthe point cloud to save
[in]precisionthe output ASCII precision

Definition at line 151 of file vtk_io.cpp.

template<std::size_t N>
void pcl::io::swapByte ( char *  bytes)

swap bytes order of a char array of length N

Parameters:
byteschar array to swap
template<typename T >
void pcl::io::swapByte ( T &  value)

swaps byte of an arbitrary type T casting it to char*

Parameters:
valuethe data you want its bytes swapped

Definition at line 451 of file common/include/pcl/common/io.h.

template<>
void pcl::io::swapByte< 1 > ( char *  bytes) [inline]

specialization of swapByte for dimension 1

Parameters:
byteschar array to swap

Definition at line 416 of file common/include/pcl/common/io.h.

template<>
void pcl::io::swapByte< 2 > ( char *  bytes) [inline]

specialization of swapByte for dimension 2

Parameters:
byteschar array to swap

Definition at line 423 of file common/include/pcl/common/io.h.

template<>
void pcl::io::swapByte< 4 > ( char *  bytes) [inline]

specialization of swapByte for dimension 4

Parameters:
byteschar array to swap

Definition at line 429 of file common/include/pcl/common/io.h.

template<>
void pcl::io::swapByte< 8 > ( char *  bytes) [inline]

specialization of swapByte for dimension 8

Parameters:
byteschar array to swap

Definition at line 439 of file common/include/pcl/common/io.h.

int pcl::io::vtk2mesh ( const vtkSmartPointer< vtkPolyData > &  poly_data,
pcl::PolygonMesh &  mesh 
)

Convert vtkPolyData object to a PCL PolygonMesh.

Parameters:
[in]poly_dataPointer (vtkSmartPointer) to a vtkPolyData object
[out]meshPCL Polygon Mesh to fill
Returns:
Number of points in the point cloud of mesh.

Definition at line 213 of file vtk_lib_io.cpp.

template<typename PointT >
void pcl::io::vtkPolyDataToPointCloud ( vtkPolyData *const  polydata,
pcl::PointCloud< PointT > &  cloud 
)

Convert a VTK PolyData object to a pcl::PointCloud one.

Parameters:
[in]polydatathe input VTK PolyData object
[out]cloudthe resultant pcl::PointCloud object

Definition at line 63 of file vtk_lib_io.hpp.

template<typename PointT >
void pcl::io::vtkStructuredGridToPointCloud ( vtkStructuredGrid *const  structured_grid,
pcl::PointCloud< PointT > &  cloud 
)

Convert a VTK StructuredGrid object to a pcl::PointCloud one.

Parameters:
[in]structured_gridthe input VTK StructuredGrid object
[out]cloudthe resultant pcl::PointCloud object

Definition at line 152 of file vtk_lib_io.hpp.



pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:18