Classes | Public Member Functions | Static Public Member Functions | Private Types | Private Attributes
pcl::PCDWriter Class Reference

Point Cloud Data (PCD) file format writer. More...

#include <pcd_io.h>

Inheritance diagram for pcl::PCDWriter:
Inheritance graph
[legend]

List of all members.

Classes

struct  ChannelPropertiesComparator
 Internal structure used to sort the ChannelProperties in the cloud.channels map based on their offset. More...

Public Member Functions

std::string generateHeaderASCII (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a PCD file format.
std::string generateHeaderBinary (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a PCD file format.
std::string generateHeaderBinaryCompressed (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a BINARY_COMPRESSED PCD file format.
std::string generateHeaderEigen (const pcl::PointCloud< Eigen::MatrixXf > &cloud, const int nr_points=std::numeric_limits< int >::max())
 Generate the header of a PCD file format.
 PCDWriter ()
void setMapSynchronization (bool sync)
 Set whether mmap() synchornization via msync() is desired before munmap() calls. Setting this to true could prevent NFS data loss (see http://www.pcl-developers.org/PCD-IO-consistency-on-NFS-msync-needed-td4885942.html). Default: false.
int write (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=false)
 Save point cloud data to a PCD file containing n-D points.
int write (const std::string &file_name, const sensor_msgs::PointCloud2::ConstPtr &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), const bool binary=false)
 Save point cloud data to a PCD file containing n-D points.
template<typename PointT >
int write (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const bool binary=false)
 Save point cloud data to a PCD file containing n-D points.
template<typename PointT >
int write (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, bool binary=false)
 Save point cloud data to a PCD file containing n-D points.
int writeASCII (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 int precision=8)
 Save point cloud data to a PCD file containing n-D points, in ASCII format.
template<typename PointT >
int writeASCII (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const int precision=8)
 Save point cloud data to a PCD file containing n-D points, in ASCII format.
template<typename PointT >
int writeASCII (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const int precision=8)
 Save point cloud data to a PCD file containing n-D points, in ASCII format.
int writeASCIIEigen (const std::string &file_name, const pcl::PointCloud< Eigen::MatrixXf > &cloud, const int precision=8)
 Save point cloud data to a PCD file containing n-D points, in ASCII format.
int writeBinary (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity())
 Save point cloud data to a PCD file containing n-D points, in BINARY format.
template<typename PointT >
int writeBinary (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Save point cloud data to a PCD file containing n-D points, in BINARY format.
template<typename PointT >
int writeBinary (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices)
 Save point cloud data to a PCD file containing n-D points, in BINARY format.
int writeBinaryCompressed (const std::string &file_name, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity())
 Save point cloud data to a PCD file containing n-D points, in BINARY_COMPRESSED format.
template<typename PointT >
int writeBinaryCompressed (const std::string &file_name, const pcl::PointCloud< PointT > &cloud)
 Save point cloud data to a binary comprssed PCD file.
int writeBinaryCompressedEigen (const std::string &file_name, const pcl::PointCloud< Eigen::MatrixXf > &cloud)
 Save point cloud data to a binary comprssed PCD file.
int writeBinaryEigen (const std::string &file_name, const pcl::PointCloud< Eigen::MatrixXf > &cloud)
 Save point cloud data to a PCD file containing n-D points, in BINARY format.
 ~PCDWriter ()

Static Public Member Functions

template<typename PointT >
static std::string generateHeader (const pcl::PointCloud< PointT > &cloud, const int nr_points=std::numeric_limits< int >::max())
 Generate the header of a PCD file format.

Private Types

typedef std::pair< std::string,
pcl::ChannelProperties
pair_channel_properties

Private Attributes

bool map_synchronization_
 Set to true if msync() should be called before munmap(). Prevents data loss on NFS systems.

Detailed Description

Point Cloud Data (PCD) file format writer.

Author:
Radu Bogdan Rusu

Definition at line 271 of file pcd_io.h.


Member Typedef Documentation

typedef std::pair<std::string, pcl::ChannelProperties> pcl::PCDWriter::pair_channel_properties [private]

Definition at line 580 of file pcd_io.h.


Constructor & Destructor Documentation

Definition at line 274 of file pcd_io.h.

Definition at line 275 of file pcd_io.h.


Member Function Documentation

template<typename PointT >
std::string pcl::PCDWriter::generateHeader ( const pcl::PointCloud< PointT > &  cloud,
const int  nr_points = std::numeric_limits<int>::max () 
) [static]

Generate the header of a PCD file format.

Parameters:
[in]cloudthe point cloud data message
[in]nr_pointsif given, use this to fill in WIDTH, HEIGHT (=1), and POINTS in the header By default, nr_points is set to INTMAX, and the data in the header is used instead.

Definition at line 73 of file pcd_io.hpp.

std::string pcl::PCDWriter::generateHeaderASCII ( const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin,
const Eigen::Quaternionf &  orientation 
)

Generate the header of a PCD file format.

Parameters:
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

Definition at line 1443 of file pcd_io.cpp.

std::string pcl::PCDWriter::generateHeaderBinary ( const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin,
const Eigen::Quaternionf &  orientation 
)

Generate the header of a PCD file format.

Parameters:
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

Definition at line 1543 of file pcd_io.cpp.

std::string pcl::PCDWriter::generateHeaderBinaryCompressed ( const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin,
const Eigen::Quaternionf &  orientation 
)

Generate the header of a BINARY_COMPRESSED PCD file format.

Parameters:
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

Definition at line 1624 of file pcd_io.cpp.

std::string pcl::PCDWriter::generateHeaderEigen ( const pcl::PointCloud< Eigen::MatrixXf > &  cloud,
const int  nr_points = std::numeric_limits<int>::max () 
)

Generate the header of a PCD file format.

Note:
This version is specialized for PointCloud<Eigen::MatrixXf> data types.
Attention:
The PCD data is always stored in ROW major format! The read/write PCD methods will detect column major input and automatically convert it.
Parameters:
[in]cloudthe point cloud data message
[in]nr_pointsif given, use this to fill in WIDTH, HEIGHT (=1), and POINTS in the header By default, nr_points is set to INTMAX, and the data in the header is used instead.

Definition at line 2066 of file pcd_io.cpp.

void pcl::PCDWriter::setMapSynchronization ( bool  sync) [inline]

Set whether mmap() synchornization via msync() is desired before munmap() calls. Setting this to true could prevent NFS data loss (see http://www.pcl-developers.org/PCD-IO-consistency-on-NFS-msync-needed-td4885942.html). Default: false.

Note:
This option should be used by advanced users only!
Please note that using msync() on certain systems can reduce the I/O performance by up to 80%!
Parameters:
[in]syncset to true if msync() should be called before munmap()

Definition at line 286 of file pcd_io.h.

int pcl::PCDWriter::write ( 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 = false 
) [inline, virtual]

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]binaryset to true if the file is to be written in a binary PCD format, 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.

As an intermediary solution, precision 8 is used, which guarantees lossless storage for RGB.

Implements pcl::FileWriter.

Definition at line 405 of file pcd_io.h.

int pcl::PCDWriter::write ( const std::string &  file_name,
const sensor_msgs::PointCloud2::ConstPtr &  cloud,
const Eigen::Vector4f &  origin = Eigen::Vector4f::Zero (),
const Eigen::Quaternionf &  orientation = Eigen::Quaternionf::Identity (),
const bool  binary = 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 (boost shared pointer)
[in]binaryset to true if the file is to be written in a binary PCD format, false (default) for ASCII
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

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.

Reimplemented from pcl::FileWriter.

Definition at line 432 of file pcd_io.h.

template<typename PointT >
int pcl::PCDWriter::write ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const bool  binary = false 
) [inline]

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

Parameters:
[in]file_namethe output file name
[in]cloudthe pcl::PointCloud data
[in]binaryset to true if the file is to be written in a binary PCD format, 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.

Reimplemented from pcl::FileWriter.

Definition at line 540 of file pcd_io.h.

template<typename PointT >
int pcl::PCDWriter::write ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const std::vector< int > &  indices,
bool  binary = false 
) [inline]

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

Parameters:
[in]file_namethe output file name
[in]cloudthe pcl::PointCloud data
[in]indicesthe set of point indices that we want written to disk
[in]binaryset to true if the file is to be written in a binary PCD format, 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 565 of file pcd_io.h.

int pcl::PCDWriter::writeASCII ( 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 int  precision = 8 
)

Save point cloud data to a PCD file containing n-D points, in ASCII format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation
[in]precisionthe specified output numeric stream precision (default: 8)

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.

As an intermediary solution, precision 8 is used, which guarantees lossless storage for RGB.

Definition at line 1677 of file pcd_io.cpp.

template<typename PointT >
int pcl::PCDWriter::writeASCII ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const int  precision = 8 
)

Save point cloud data to a PCD file containing n-D points, in ASCII format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]precisionthe specified output numeric stream precision (default: 8)

Definition at line 435 of file pcd_io.hpp.

template<typename PointT >
int pcl::PCDWriter::writeASCII ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const std::vector< int > &  indices,
const int  precision = 8 
)

Save point cloud data to a PCD file containing n-D points, in ASCII format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]indicesthe set of point indices that we want written to disk
[in]precisionthe specified output numeric stream precision (default: 8)

Definition at line 718 of file pcd_io.hpp.

int pcl::PCDWriter::writeASCIIEigen ( const std::string &  file_name,
const pcl::PointCloud< Eigen::MatrixXf > &  cloud,
const int  precision = 8 
)

Save point cloud data to a PCD file containing n-D points, in ASCII format.

Note:
This version is specialized for PointCloud<Eigen::MatrixXf> data types.
Attention:
The PCD data is always stored in ROW major format! The read/write PCD methods will detect column major input and automatically convert it.
Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]precisionthe specified output numeric stream precision (default: 8)

Definition at line 2120 of file pcd_io.cpp.

int pcl::PCDWriter::writeBinary ( const std::string &  file_name,
const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin = Eigen::Vector4f::Zero (),
const Eigen::Quaternionf &  orientation = Eigen::Quaternionf::Identity () 
)

Save point cloud data to a PCD file containing n-D points, in BINARY format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

Definition at line 1785 of file pcd_io.cpp.

template<typename PointT >
int pcl::PCDWriter::writeBinary ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud 
)

Save point cloud data to a PCD file containing n-D points, in BINARY format.

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

Definition at line 125 of file pcd_io.hpp.

template<typename PointT >
int pcl::PCDWriter::writeBinary ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud,
const std::vector< int > &  indices 
)

Save point cloud data to a PCD file containing n-D points, in BINARY format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]indicesthe set of point indices that we want written to disk

Definition at line 590 of file pcd_io.hpp.

int pcl::PCDWriter::writeBinaryCompressed ( const std::string &  file_name,
const sensor_msgs::PointCloud2 &  cloud,
const Eigen::Vector4f &  origin = Eigen::Vector4f::Zero (),
const Eigen::Quaternionf &  orientation = Eigen::Quaternionf::Identity () 
)

Save point cloud data to a PCD file containing n-D points, in BINARY_COMPRESSED format.

Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message
[in]originthe sensor acquisition origin
[in]orientationthe sensor acquisition orientation

Definition at line 1882 of file pcd_io.cpp.

template<typename PointT >
int pcl::PCDWriter::writeBinaryCompressed ( const std::string &  file_name,
const pcl::PointCloud< PointT > &  cloud 
)

Save point cloud data to a binary comprssed PCD file.

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

Definition at line 252 of file pcd_io.hpp.

int pcl::PCDWriter::writeBinaryCompressedEigen ( const std::string &  file_name,
const pcl::PointCloud< Eigen::MatrixXf > &  cloud 
)

Save point cloud data to a binary comprssed PCD file.

Note:
This version is specialized for PointCloud<Eigen::MatrixXf> data types.
Attention:
The PCD data is always stored in ROW major format! The read/write PCD methods will detect column major input and automatically convert it.
Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data message

Definition at line 2280 of file pcd_io.cpp.

int pcl::PCDWriter::writeBinaryEigen ( const std::string &  file_name,
const pcl::PointCloud< Eigen::MatrixXf > &  cloud 
)

Save point cloud data to a PCD file containing n-D points, in BINARY format.

Note:
This version is specialized for PointCloud<Eigen::MatrixXf> data types.
Attention:
The PCD data is always stored in ROW major format! The read/write PCD methods will detect column major input and automatically convert it.
Parameters:
[in]file_namethe output file name
[in]cloudthe point cloud data

Definition at line 2175 of file pcd_io.cpp.


Member Data Documentation

Set to true if msync() should be called before munmap(). Prevents data loss on NFS systems.

Definition at line 578 of file pcd_io.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:19:48