pcl::io Namespace Reference

Functions

template<typename PointT >
int loadPCDFile (const std::string &file_name, pcl::PointCloud< PointT > &cloud)
 Load any PCD 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.
int loadPCDFile (const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
 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.
template<typename PointT >
int 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.
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.
int 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 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. This version is to retain backwards compatibility.
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. This version is to retain backwards compatibility.
int saveVTKFile (const std::string &file_name, const pcl::PolygonMesh &triangles, unsigned precision=5)
 Saves a PolygonMesh in ascii VTK format.

Function Documentation

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 279 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 265 of file pcd_io.h.

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 251 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,
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
indices the set of indices to save
binary_mode true for binary mode, false (default) for ASCII

Definition at line 353 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

Definition at line 310 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

Definition at line 294 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

Definition at line 324 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 338 of file pcd_io.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:
file_name the name of the file to write to disk
triangles the polygonal mesh to save
precision the output ASCII precision

Definition at line 45 of file vtk_io.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:23 2013