pcd_io.h File Reference

#include "pcl/io/io.h"
Include dependency graph for pcd_io.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  pcl::PCDReader
 Point Cloud Data (PCD) file format reader. More...
class  pcl::PCDWriter
 Point Cloud Data (PCD) file format writer. More...

Namespaces

namespace  pcl
namespace  pcl::io

Functions

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::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 pcl::io::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 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.
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.
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::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 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. This version is to retain backwards compatibility.
 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:56:13 2013