Namespaces | Classes | Enumerations | Functions | Variables
pcl::io Namespace Reference

Namespaces

namespace  ply

Classes

struct  CameraParameters
 Basic camera parameters placeholder. More...
struct  CompressionPointTraits
struct  CompressionPointTraits< PointXYZRGB >
struct  CompressionPointTraits< PointXYZRGBA >
struct  configurationProfile_t
class  DeBayer
 Various debayering methods. More...
class  LZFBayer8ImageReader
 PCL-LZF 8-bit Bayer image format reader. More...
class  LZFBayer8ImageWriter
 PCL-LZF 8-bit Bayer image format writer. More...
class  LZFDepth16ImageReader
 PCL-LZF 16-bit depth image format reader. More...
class  LZFDepth16ImageWriter
 PCL-LZF 16-bit depth image format writer. More...
class  LZFImageReader
 PCL-LZF image format reader. The PCL-LZF image format is nothing else but a LZF-modified compression over an existing file type (e.g., PNG). However, in certain situations, like RGB data for example, an [RGBRGB...RGB] array will be first reordered into [RR...RGG...GBB...B] in order to ensure better compression. More...
class  LZFImageWriter
 PCL-LZF image format writer. The PCL-LZF image format is nothing else but a LZF-modified compression over an existing file type (e.g., PNG). However, in certain situations, like RGB data for example, an [RGBRGB...RGB] array will be first reordered into [RR...RGG...GBB...B] in order to ensure better compression. More...
class  LZFRGB24ImageReader
 PCL-LZF 24-bit RGB image format reader. More...
class  LZFRGB24ImageWriter
 PCL-LZF 24-bit RGB image format writer. More...
class  LZFYUV422ImageReader
 PCL-LZF 8-bit Bayer image format reader. More...
class  LZFYUV422ImageWriter
 PCL-LZF 16-bit YUV422 image format writer. More...
class  OctreePointCloudCompression
 Octree pointcloud compression class More...
struct  OrganizedConversion< PointT, false >
struct  OrganizedConversion< PointT, true >
class  OrganizedPointCloudCompression
struct  TARHeader
 A TAR file's header, as described on http://en.wikipedia.org/wiki/Tar_%28file_format%29. More...

Enumerations

enum  compression_Profiles_e {
  LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, LOW_RES_ONLINE_COMPRESSION_WITH_COLOR, MED_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, MED_RES_ONLINE_COMPRESSION_WITH_COLOR,
  HIGH_RES_ONLINE_COMPRESSION_WITHOUT_COLOR, HIGH_RES_ONLINE_COMPRESSION_WITH_COLOR, LOW_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, LOW_RES_OFFLINE_COMPRESSION_WITH_COLOR,
  MED_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, MED_RES_OFFLINE_COMPRESSION_WITH_COLOR, HIGH_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR, HIGH_RES_OFFLINE_COMPRESSION_WITH_COLOR,
  COMPRESSION_PROFILE_COUNT, MANUAL_CONFIGURATION
}

Functions

template<typename T >
void decodePNGImage (typename std::vector< uint8_t > &pngData_arg, typename std::vector< T > &imageData_arg, size_t &width_arg, size_t &height_arg, unsigned int &channels_arg)
PCL_EXPORTS void decodePNGToImage (std::vector< uint8_t > &pngData_arg, std::vector< uint8_t > &imageData_arg, size_t &width_arg, size_t &heigh_argt, unsigned int &channels_arg)
 Decode compressed PNG to 8-bit image.
PCL_EXPORTS void decodePNGToImage (std::vector< uint8_t > &pngData_arg, std::vector< uint16_t > &imageData_arg, size_t &width_arg, size_t &height_arg, unsigned int &channels_arg)
 Decode compressed PNG to 16-bit image.
template<typename T >
void encodeImageToPNG (typename std::vector< T > &image_arg, size_t width_arg, size_t height_arg, int image_format_arg, typename std::vector< uint8_t > &pngData_arg, int png_level_arg)
PCL_EXPORTS void encodeMonoImageToPNG (std::vector< uint8_t > &image_arg, size_t width_arg, size_t height_arg, std::vector< uint8_t > &pngData_arg, int png_level_arg=-1)
 Encodes 8-bit mono image to PNG format.
PCL_EXPORTS void encodeMonoImageToPNG (std::vector< uint16_t > &image_arg, size_t width_arg, size_t height_arg, std::vector< uint8_t > &pngData_arg, int png_level_arg=-1)
 Encodes 16-bit mono image to PNG format.
PCL_EXPORTS void encodeRGBImageToPNG (std::vector< uint8_t > &image_arg, size_t width_arg, size_t height_arg, std::vector< uint8_t > &pngData_arg, int png_level_arg=-1)
 Encodes 8-bit RGB image to PNG format.
PCL_EXPORTS void encodeRGBImageToPNG (std::vector< uint16_t > &image_arg, size_t width_arg, size_t height_arg, std::vector< uint8_t > &pngData_arg, int png_level_arg=-1)
 Encodes 16-bit RGB image to PNG format.
int loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &cloud)
 Load a PCD v.6 file into a templated PointCloud type.
int loadPCDFile (const std::string &file_name, pcl::PCLPointCloud2 &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, pcl::PCLPointCloud2 &cloud)
 Load a PLY v.6 file into a templated PointCloud type.
int loadPLYFile (const std::string &file_name, pcl::PCLPointCloud2 &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 loadPolygonFileOBJ (const std::string &file_name, pcl::TextureMesh &mesh)
 Load an OBJ file into a TextureMesh 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.
PCL_EXPORTS void pointCloudTovtkPolyData (const pcl::PCLPointCloud2Ptr &cloud, vtkSmartPointer< vtkPolyData > &poly_data)
 Convert a PCLPointCloud2 object to a VTK PolyData object.
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 void saveCharPNGFile (const std::string &file_name, const unsigned char *mono_image, int width, int height, int channels)
 Saves 8-bit encoded image to PNG file.
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 pcl::PCLPointCloud2 &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. The resulting file will be an uncompressed binary.
template<typename PointT >
int savePCDFileBinaryCompressed (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. This method will write a compressed binary file.
int savePLYFile (const std::string &file_name, const pcl::PCLPointCloud2 &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 savePLYFileBinary (const std::string &file_name, const pcl::PolygonMesh &mesh)
 Saves a PolygonMesh in binary PLY format.
void savePNGFile (const std::string &file_name, const pcl::PointCloud< unsigned char > &cloud)
 Saves 8-bit grayscale cloud as image to PNG file.
void savePNGFile (const std::string &file_name, const pcl::PointCloud< unsigned short > &cloud)
 Saves 16-bit grayscale cloud as image to PNG file.
template<typename T >
void savePNGFile (const std::string &file_name, const pcl::PointCloud< T > &cloud)
 Saves RGB fields of cloud as image to PNG file.
void savePNGFile (const std::string &file_name, const pcl::PointCloud< pcl::PointXYZL > &cloud)
 Saves Labeled Point cloud as image to PNG file.
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 void saveRgbPNGFile (const std::string &file_name, const unsigned char *rgb_image, int width, int height)
 Saves 8-bit encoded RGB image to PNG file.
PCL_EXPORTS void saveShortPNGFile (const std::string &file_name, const unsigned short *short_image, int width, int height, int channels)
 Saves 16-bit encoded image to PNG file.
template<typename PointT >
bool saveTARPointCloud (const std::string &tar_filename, const PointCloud< PointT > &cloud, const std::string &pcd_filename)
 Save a PointCloud dataset into a TAR file. Append if the file exists, or create a new one if not.
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 pcl::PCLPointCloud2 &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.
PCL_EXPORTS int vtk2mesh (const vtkSmartPointer< vtkPolyData > &poly_data, pcl::TextureMesh &mesh)
 Convert vtkPolyData object to a PCL TextureMesh.
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.

Variables

struct configurationProfile_t compressionProfiles_ [COMPRESSION_PROFILE_COUNT]

Enumeration Type Documentation

Enumerator:
LOW_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 
LOW_RES_ONLINE_COMPRESSION_WITH_COLOR 
MED_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 
MED_RES_ONLINE_COMPRESSION_WITH_COLOR 
HIGH_RES_ONLINE_COMPRESSION_WITHOUT_COLOR 
HIGH_RES_ONLINE_COMPRESSION_WITH_COLOR 
LOW_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 
LOW_RES_OFFLINE_COMPRESSION_WITH_COLOR 
MED_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 
MED_RES_OFFLINE_COMPRESSION_WITH_COLOR 
HIGH_RES_OFFLINE_COMPRESSION_WITHOUT_COLOR 
HIGH_RES_OFFLINE_COMPRESSION_WITH_COLOR 
COMPRESSION_PROFILE_COUNT 
MANUAL_CONFIGURATION 

Definition at line 45 of file compression_profiles.h.


Function Documentation

template<typename T >
void pcl::io::decodePNGImage ( typename std::vector< uint8_t > &  pngData_arg,
typename std::vector< T > &  imageData_arg,
size_t &  width_arg,
size_t &  height_arg,
unsigned int &  channels_arg 
)

Definition at line 177 of file libpng_wrapper.cpp.

void pcl::io::decodePNGToImage ( std::vector< uint8_t > &  pngData_arg,
std::vector< uint8_t > &  imageData_arg,
size_t &  width_arg,
size_t &  heigh_argt,
unsigned int &  channels_arg 
)

Decode compressed PNG to 8-bit image.

Parameters:
[in]pngDataPNG compressed input data
[in]imageDataimage output data
[out]widthimage width
[out]heightimage height
[out]channelsnumber of channels

Definition at line 315 of file libpng_wrapper.cpp.

void pcl::io::decodePNGToImage ( std::vector< uint8_t > &  pngData_arg,
std::vector< uint16_t > &  imageData_arg,
size_t &  width_arg,
size_t &  height_arg,
unsigned int &  channels_arg 
)

Decode compressed PNG to 16-bit image.

Parameters:
[in]pngDataPNG compressed input data
[in]imageDataimage output data
[out]widthimage width
[out]heightimage height
[out]channelsnumber of channels

Definition at line 326 of file libpng_wrapper.cpp.

template<typename T >
void pcl::io::encodeImageToPNG ( typename std::vector< T > &  image_arg,
size_t  width_arg,
size_t  height_arg,
int  image_format_arg,
typename std::vector< uint8_t > &  pngData_arg,
int  png_level_arg 
)

Definition at line 84 of file libpng_wrapper.cpp.

void pcl::io::encodeMonoImageToPNG ( std::vector< uint8_t > &  image_arg,
size_t  width_arg,
size_t  height_arg,
std::vector< uint8_t > &  pngData_arg,
int  png_level_arg = -1 
)

Encodes 8-bit mono image to PNG format.

Parameters:
[in]image_arginput image data
[in]width_argimage width
[in]height_argimage height
[out]pngDataPNG compressed image data
[in]png_level_argzLib compression level (default level: -1)

Definition at line 263 of file libpng_wrapper.cpp.

void pcl::io::encodeMonoImageToPNG ( std::vector< uint16_t > &  image_arg,
size_t  width_arg,
size_t  height_arg,
std::vector< uint8_t > &  pngData_arg,
int  png_level_arg = -1 
)

Encodes 16-bit mono image to PNG format.

Parameters:
[in]image_arginput image data
[in]width_argimage width
[in]height_argimage height
[out]pngDataPNG compressed image data
[in]png_level_argzLib compression level (default level: -1)

Definition at line 276 of file libpng_wrapper.cpp.

void pcl::io::encodeRGBImageToPNG ( std::vector< uint8_t > &  image_arg,
size_t  width_arg,
size_t  height_arg,
std::vector< uint8_t > &  pngData_arg,
int  png_level_arg = -1 
)

Encodes 8-bit RGB image to PNG format.

Parameters:
[in]image_arginput image data
[in]width_argimage width
[in]height_argimage height
[out]pngDataPNG compressed image data
[in]png_level_argzLib compression level (default level: -1)

Definition at line 289 of file libpng_wrapper.cpp.

void pcl::io::encodeRGBImageToPNG ( std::vector< uint16_t > &  image_arg,
size_t  width_arg,
size_t  height_arg,
std::vector< uint8_t > &  pngData_arg,
int  png_level_arg = -1 
)

Encodes 16-bit RGB image to PNG format.

Parameters:
[in]image_arginput image data
[in]width_argimage width
[in]height_argimage height
[out]pngDataPNG compressed image data
[in]png_level_argzLib compression level (default level: -1)

Definition at line 302 of file libpng_wrapper.cpp.

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

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

Any PCD files > v.6 will generate a warning as a pcl/PCLPointCloud2 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 512 of file pcd_io.h.

int pcl::io::loadPCDFile ( const std::string file_name,
pcl::PCLPointCloud2 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 527 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 541 of file pcd_io.h.

int pcl::io::loadPLYFile ( const std::string file_name,
pcl::PCLPointCloud2 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 pcl/PCLPointCloud2 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 800 of file ply_io.h.

int pcl::io::loadPLYFile ( const std::string file_name,
pcl::PCLPointCloud2 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 815 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 829 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 50 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 133 of file vtk_lib_io.cpp.

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

Load an OBJ file into a TextureMesh object.

Note:
In addition to the loadPolygonFileOBJ (const std::string, pcl::PolygonMesh&) method, this method also loads the uv-coordinates from the file. It does not load the material information.
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 146 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 119 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 160 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 105 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 385 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 280 of file vtk_lib_io.hpp.

void pcl::io::pointCloudTovtkPolyData ( const pcl::PCLPointCloud2Ptr cloud,
vtkSmartPointer< vtkPolyData > &  poly_data 
)

Convert a PCLPointCloud2 object to a VTK PolyData object.

Parameters:
[in]cloudthe input PCLPointCloud2Ptr object
[out]poly_datathe resultant VTK PolyData object

Definition at line 520 of file vtk_lib_io.cpp.

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 392 of file vtk_lib_io.hpp.

void pcl::io::saveCharPNGFile ( const std::string file_name,
const unsigned char *  mono_image,
int  width,
int  height,
int  channels 
)

Saves 8-bit encoded image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]mono_imageimage grayscale data
[in]widthimage width
[in]heightimage height
[in]channelsnumber of channels

Definition at line 66 of file png_io.cpp.

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 pcl::PCLPointCloud2 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 563 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 587 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 650 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 610 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. The resulting file will be an uncompressed binary.

This version is to retain backwards compatibility.

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

Definition at line 626 of file pcd_io.h.

template<typename PointT >
int pcl::io::savePCDFileBinaryCompressed ( 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 method will write a compressed binary file.

This version is to retain backwards compatibility.

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

Definition at line 671 of file pcd_io.h.

int pcl::io::savePLYFile ( const std::string file_name,
const pcl::PCLPointCloud2 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 844 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 861 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 900 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 1543 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 874 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 886 of file ply_io.h.

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

Saves a PolygonMesh in binary PLY format.

Parameters:
[in]file_namethe name of the file to write to disk
[in]meshthe polygonal mesh to save

Definition at line 1663 of file ply_io.cpp.

void pcl::io::savePNGFile ( const std::string file_name,
const pcl::PointCloud< unsigned char > &  cloud 
)

Saves 8-bit grayscale cloud as image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]cloudpoint cloud to save

Definition at line 94 of file png_io.h.

void pcl::io::savePNGFile ( const std::string file_name,
const pcl::PointCloud< unsigned short > &  cloud 
)

Saves 16-bit grayscale cloud as image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]cloudpoint cloud to save

Definition at line 106 of file png_io.h.

template<typename T >
void pcl::io::savePNGFile ( const std::string file_name,
const pcl::PointCloud< T > &  cloud 
)

Saves RGB fields of cloud as image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]cloudpoint cloud to save

Definition at line 117 of file png_io.h.

void pcl::io::savePNGFile ( const std::string file_name,
const pcl::PointCloud< pcl::PointXYZL > &  cloud 
)

Saves Labeled Point cloud as image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]cloudpoint cloud to save

Warning: Converts to 16 bit (for png), labels using more than 16 bits will cause problems

Definition at line 137 of file png_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 77 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 190 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 207 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 174 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 481 of file vtk_lib_io.cpp.

PCL_EXPORTS void pcl::io::saveRgbPNGFile ( const std::string file_name,
const unsigned char *  rgb_image,
int  width,
int  height 
)

Saves 8-bit encoded RGB image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]rgb_imageimage rgb data
[in]widthimage width
[in]heightimage height

Definition at line 83 of file png_io.h.

void pcl::io::saveShortPNGFile ( const std::string file_name,
const unsigned short *  short_image,
int  width,
int  height,
int  channels 
)

Saves 16-bit encoded image to PNG file.

Parameters:
[in]file_namethe name of the file to write to disk
[in]short_imageimage short data
[in]widthimage width
[in]heightimage height
[in]channelsnumber of channels

Definition at line 82 of file png_io.cpp.

template<typename PointT >
bool pcl::io::saveTARPointCloud ( const std::string tar_filename,
const PointCloud< PointT > &  cloud,
const std::string pcd_filename 
)

Save a PointCloud dataset into a TAR file. Append if the file exists, or create a new one if not.

Parameters:
[in]tar_filenamethe name of the TAR file to save the cloud to
[in]cloudthe point cloud dataset to save
[in]pcd_filenamethe internal name of the PCD file that should be stored in the TAR header
Remarks:
till implemented will return FALSE

Definition at line 94 of file tar.h.

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 pcl::PCLPointCloud2 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<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 480 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 445 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 452 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 458 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 468 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 223 of file vtk_lib_io.cpp.

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

Convert vtkPolyData object to a PCL TextureMesh.

Note:
In addition to the vtk2mesh (const vtkSmartPointer<vtkPolyData>&, pcl::PolygonMesh&) method, it fills the mesh with the uv-coordinates.
Parameters:
[in]poly_dataPointer (vtkSmartPointer) to a vtkPolyData object
[out]meshPCL TextureMesh to fill
Returns:
Number of points in the point cloud of mesh.

TODO avoid copying here

TODO check for sub-meshes

Definition at line 345 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 65 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 154 of file vtk_lib_io.hpp.


Variable Documentation

Definition at line 81 of file compression_profiles.h.



pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:58