Go to the source code of this file.
Classes | |
struct | pcl::PCDWriter::ChannelPropertiesComparator |
Internal structure used to sort the ChannelProperties in the cloud.channels map based on their offset. More... | |
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 | |
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 (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 | 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::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 | 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. |