Classes | Functions

Module io


Detailed Description

Overview

The pcl_io library contains classes and functions for reading and writing point cloud data and capturing from OpenNI-compatible depth cameras. An introduction to some of these capabilities can be found in the following tutorials.

History

Requirements

Classes

class  pcl::FileReader
 Point Cloud Data (FILE) file format reader interface. More...
class  pcl::FileWriter
 Point Cloud Data (FILE) file format writer. More...
class  pcl::Grabber
 Grabber interface for PCL 1.x device drivers. More...
class  openni_wrapper::OpenNIDevice
 Class representing an astract device for Primesense or MS Kinect devices. More...
class  openni_wrapper::DeviceKinect
 Concrete implementation of the interface OpenNIDevice for a MS Kinect device. More...
class  openni_wrapper::DeviceONI
 Concrete implementation of the interface OpenNIDevice for a virtual device playing back an ONI file. More...
class  openni_wrapper::DevicePrimesense
 Concrete implementation of the interface OpenNIDevice for a Primesense device. More...
class  openni_wrapper::DeviceXtionPro
 Concrete implementation of the interface OpenNIDevice for a Asus Xtion Pro device. More...
class  openni_wrapper::OpenNIDriver
 Driver class implemented as Singleton. More...
class  openni_wrapper::OpenNIException
 General exception class. More...
class  openni_wrapper::Image
 Image class containing just a reference to image meta data. More...
class  openni_wrapper::ImageBayerGRBG
 This class provides methods to fill a RGB or Grayscale image buffer from underlying Bayer pattern image. More...
class  openni_wrapper::ImageRGB24
 This class provides methods to fill a RGB or Grayscale image buffer from underlying RGB24 image. More...
class  openni_wrapper::ImageYUV422
 Concrete implementation of the interface Image for a YUV 422 image used by Primesense devices. More...
class  pcl::PCDGrabberBase
 Base class for PCD file grabber. More...
class  pcl::PCDReader
 Point Cloud Data (PCD) file format reader. More...
class  pcl::PCDWriter
 Point Cloud Data (PCD) file format writer. More...
class  pcl::PLYReader
 Point Cloud Data (PLY) file format reader. More...
class  pcl::PLYWriter
 Point Cloud Data (PLY) file format writer. More...

Functions

int pcl::getFieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
 Get the index of a specified field (i.e., dimension/channel).
template<typename PointT >
int pcl::getFieldIndex (const pcl::PointCloud< PointT > &cloud, const std::string &field_name, std::vector< sensor_msgs::PointField > &fields)
 Get the index of a specified field (i.e., dimension/channel).
template<typename PointT >
void pcl::getFields (const pcl::PointCloud< PointT > &cloud, std::vector< sensor_msgs::PointField > &fields)
 Get the list of available fields (i.e., dimension/channel).
template<typename PointT >
std::string pcl::getFieldsList (const pcl::PointCloud< PointT > &cloud)
 Get the list of all fields available in a given cloud.
std::string pcl::getFieldsList (const sensor_msgs::PointCloud2 &cloud)
 Get the available point cloud fields as a space separated string.
int pcl::getFieldSize (int datatype)
 Obtains the size of a specific field data type in bytes.
int pcl::getFieldType (int size, char type)
 Obtains the type of the PointField from a specific size and type.
char pcl::getFieldType (int type)
 Obtains the type of the PointField from a specific PointField as a char.
template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
 Copy all the fields from a given point cloud into a new point cloud.
PCL_EXPORTS bool pcl::concatenatePointCloud (const sensor_msgs::PointCloud2 &cloud1, const sensor_msgs::PointCloud2 &cloud2, sensor_msgs::PointCloud2 &cloud_out)
 Concatenate two sensor_msgs::PointCloud2.
PCL_EXPORTS void pcl::copyPointCloud (const sensor_msgs::PointCloud2 &cloud_in, const std::vector< int > &indices, sensor_msgs::PointCloud2 &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointT >
void pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const std::vector< int > &indices, pcl::PointCloud< PointOutT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointT >
void pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const PointIndices &indices, pcl::PointCloud< PointT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const PointIndices &indices, pcl::PointCloud< PointOutT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointT >
void pcl::copyPointCloud (const pcl::PointCloud< PointT > &cloud_in, const std::vector< pcl::PointIndices > &indices, pcl::PointCloud< PointT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud (const pcl::PointCloud< PointInT > &cloud_in, const std::vector< pcl::PointIndices > &indices, pcl::PointCloud< PointOutT > &cloud_out)
 Extract the indices of a given point cloud as a new point cloud.
template<typename PointIn1T , typename PointIn2T , typename PointOutT >
void pcl::concatenateFields (const pcl::PointCloud< PointIn1T > &cloud1_in, const pcl::PointCloud< PointIn2T > &cloud2_in, pcl::PointCloud< PointOutT > &cloud_out)
 Concatenate two datasets representing different fields.
PCL_EXPORTS bool pcl::getPointCloudAsEigen (const sensor_msgs::PointCloud2 &in, Eigen::MatrixXf &out)
 Copy the XYZ dimensions of a sensor_msgs::PointCloud2 into Eigen format.
PCL_EXPORTS bool pcl::getEigenAsPointCloud (Eigen::MatrixXf &in, sensor_msgs::PointCloud2 &out)
 Copy the XYZ dimensions from an Eigen MatrixXf into a sensor_msgs::PointCloud2 message.
template<std::size_t N>
void pcl::io::swapByte (char *bytes)
 swap bytes order of a char array of length N
int pcl::io::loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 Load a PCD v.6 file into a templated PointCloud type.
int pcl::io::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 pcl::io::loadPCDFile (const std::string &file_name, pcl::PointCloud< PointT > &cloud)
 Load any PCD file into a templated PointCloud type.
int pcl::io::savePCDFile (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)
 Save point cloud data to a PCD file containing n-D points.
template<typename PointT >
int pcl::io::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 pcl::io::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 pcl::io::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.
template<typename PointT >
int pcl::io::savePCDFile (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 PCD file containing a specific given cloud format.
int pcl::io::loadPLYFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 Load a PLY v.6 file into a templated PointCloud type.
int pcl::io::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 pcl::io::loadPLYFile (const std::string &file_name, pcl::PointCloud< PointT > &cloud)
 Load any PLY file into a templated PointCloud type.
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)
 Save point cloud data to a PLY file containing n-D points.
template<typename PointT >
int pcl::io::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 pcl::io::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 pcl::io::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.
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.
PCL_EXPORTS int pcl::io::saveVTKFile (const std::string &file_name, const pcl::PolygonMesh &triangles, unsigned precision=5)
 Saves a PolygonMesh in ascii VTK format.

Function Documentation

template<typename PointIn1T , typename PointIn2T , typename PointOutT >
void pcl::concatenateFields ( const pcl::PointCloud< PointIn1T > &  cloud1_in,
const pcl::PointCloud< PointIn2T > &  cloud2_in,
pcl::PointCloud< PointOutT > &  cloud_out 
)

Concatenate two datasets representing different fields.

Parameters:
cloud1_in the first input dataset
cloud2_in the second input dataset
cloud_out the resultant output dataset created by the concatenation of all the fields in the input datasets

Definition at line 283 of file io.hpp.

PCL_EXPORTS bool pcl::concatenatePointCloud ( const sensor_msgs::PointCloud2 cloud1,
const sensor_msgs::PointCloud2 cloud2,
sensor_msgs::PointCloud2 cloud_out 
)

Concatenate two sensor_msgs::PointCloud2.

Returns true if successful, false if failed (e.g., name/number of fields differs)

Parameters:
cloud1 the first input point cloud dataset
cloud2 the second input point cloud dataset
cloud_out the resultant output point cloud dataset
template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
pcl::PointCloud< PointOutT > &  cloud_out 
)

Copy all the fields from a given point cloud into a new point cloud.

Parameters:
cloud_in the input point cloud dataset
cloud_out the resultant output point cloud dataset

Definition at line 81 of file io.hpp.

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const std::vector< pcl::PointIndices > &  indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the vector of indices representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 244 of file io.hpp.

template<typename PointT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const std::vector< pcl::PointIndices > &  indices,
pcl::PointCloud< PointT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the vector of indices representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 207 of file io.hpp.

PCL_EXPORTS void pcl::copyPointCloud ( const sensor_msgs::PointCloud2 cloud_in,
const std::vector< int > &  indices,
sensor_msgs::PointCloud2 cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the vector of indices representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset
template<typename PointT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const std::vector< int > &  indices,
pcl::PointCloud< PointT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the vector of indices representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 103 of file io.hpp.

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const std::vector< int > &  indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the vector of indices representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 128 of file io.hpp.

template<typename PointT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointT > &  cloud_in,
const PointIndices &  indices,
pcl::PointCloud< PointT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the PointIndices structure representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 155 of file io.hpp.

template<typename PointInT , typename PointOutT >
void pcl::copyPointCloud ( const pcl::PointCloud< PointInT > &  cloud_in,
const PointIndices &  indices,
pcl::PointCloud< PointOutT > &  cloud_out 
)

Extract the indices of a given point cloud as a new point cloud.

Parameters:
cloud_in the input point cloud dataset
indices the PointIndices structure representing the points to be copied from cloud_in
cloud_out the resultant output point cloud dataset

Definition at line 180 of file io.hpp.

PCL_EXPORTS bool pcl::getEigenAsPointCloud ( Eigen::MatrixXf &  in,
sensor_msgs::PointCloud2 out 
)

Copy the XYZ dimensions from an Eigen MatrixXf into a sensor_msgs::PointCloud2 message.

Parameters:
in the Eigen MatrixXf format containing XYZ0 / point
out the resultant point cloud message
Note:
the method assumes that the PointCloud2 message already has the fields set up properly !
template<typename PointT >
int pcl::getFieldIndex ( const pcl::PointCloud< PointT > &  cloud,
const std::string &  field_name,
std::vector< sensor_msgs::PointField > &  fields 
) [inline]

Get the index of a specified field (i.e., dimension/channel).

Parameters:
cloud the the point cloud message
field_name the string defining the field name
fields a vector to the original PointField vector that the raw PointCloud message contains

Definition at line 45 of file io.hpp.

int pcl::getFieldIndex ( const sensor_msgs::PointCloud2 cloud,
const std::string &  field_name 
) [inline]

Get the index of a specified field (i.e., dimension/channel).

Parameters:
cloud the the point cloud message
field_name the string defining the field name

Definition at line 56 of file io.h.

template<typename PointT >
void pcl::getFields ( const pcl::PointCloud< PointT > &  cloud,
std::vector< sensor_msgs::PointField > &  fields 
) [inline]

Get the list of available fields (i.e., dimension/channel).

Parameters:
cloud the the point cloud message
fields a vector to the original PointField vector that the raw PointCloud message contains

Definition at line 58 of file io.hpp.

int pcl::getFieldSize ( int  datatype  )  [inline]

Obtains the size of a specific field data type in bytes.

Parameters:
datatype the field data type (see PointField.h)

Definition at line 109 of file io.h.

template<typename PointT >
std::string pcl::getFieldsList ( const pcl::PointCloud< PointT > &  cloud  )  [inline]

Get the list of all fields available in a given cloud.

Parameters:
cloud the the point cloud message

Definition at line 67 of file io.hpp.

std::string pcl::getFieldsList ( const sensor_msgs::PointCloud2 cloud  )  [inline]

Get the available point cloud fields as a space separated string.

Parameters:
cloud a pointer to the PointCloud message

Definition at line 95 of file io.h.

char pcl::getFieldType ( int  type  )  [inline]

Obtains the type of the PointField from a specific PointField as a char.

Parameters:
type the PointField field type

Definition at line 178 of file io.h.

int pcl::getFieldType ( int  size,
char  type 
) [inline]

Obtains the type of the PointField from a specific size and type.

Parameters:
size the size in bytes of the data field
type a char describing the type of the field ('F' = float, 'I' = signed, 'U' = unsigned)

Definition at line 140 of file io.h.

PCL_EXPORTS bool pcl::getPointCloudAsEigen ( const sensor_msgs::PointCloud2 in,
Eigen::MatrixXf &  out 
)

Copy the XYZ dimensions of a sensor_msgs::PointCloud2 into Eigen format.

Parameters:
in the point cloud message
out the resultant Eigen MatrixXf format containing XYZ0 / point
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:
file_name the name of the file to load
cloud the resultant templated point cloud

Definition at line 301 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:
file_name the name of the file to load
cloud the resultant templated point cloud
origin the sensor acquisition origin (only for > PCD_V7 - null if not present)
orientation the sensor acquisition orientation (only for > PCD_V7 - identity if not present)

Definition at line 316 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:
file_name the name of the file to load
cloud the resultant templated point cloud

Definition at line 330 of file pcd_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:
file_name the name of the file to load
cloud the resultant templated point cloud

Definition at line 304 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:
file_name the name of the file to load
cloud the resultant templated point cloud
origin the sensor acquisition origin (only for > PLY_V7 - null if not present)
orientation the sensor acquisition orientation if availble, identity if not present

Definition at line 290 of file ply_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:
file_name the name of the file to load
cloud the resultant templated point cloud

Definition at line 275 of file ply_io.h.

template<typename PointT >
int pcl::io::savePCDFile ( 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 PCD file containing a specific given cloud format.

Parameters:
file_name the output file name
cloud the point cloud data message
indices the set of indices to save
binary_mode true 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 440 of file pcd_io.h.

int pcl::io::savePCDFile ( 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 
) [inline]

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

Parameters:
file_name the output file name
cloud the point cloud data message
origin the sensor acquisition origin
orientation the sensor acquisition orientation
binary_mode true 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 352 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:
file_name the output file name
cloud the point cloud data message
binary_mode true 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 376 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:
file_name the output file name
cloud the 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 399 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:
file_name the output file name
cloud the point cloud data message

Definition at line 415 of file pcd_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:
file_name the output file name
cloud the point cloud data message
indices the set of indices to save
binary_mode true for binary mode, false (default) for ASCII

Definition at line 378 of file ply_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 
) [inline]

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

Parameters:
file_name the output file name
cloud the point cloud data message
binary_mode true for binary mode, false (default) for ASCII

Definition at line 317 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:
file_name the output file name
cloud the point cloud data message
binary_mode true for binary mode, false (default) for ASCII

Definition at line 334 of file ply_io.h.

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:
file_name the output file name
cloud the point cloud data message

Definition at line 348 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.

Definition at line 360 of file ply_io.h.

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

Saves a PolygonMesh in ascii VTK format.

Parameters:
file_name the name of the file to write to disk
triangles the polygonal mesh to save
precision the output ASCII precision
template<std::size_t N>
void pcl::io::swapByte ( char *  bytes  ) 

swap bytes order of a char array of length N

Parameters:
bytes char array to swap