Public Member Functions | Static Public Member Functions | Protected Member Functions | 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.

Public Member Functions

std::string generateHeaderASCII (const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a PCD file format.
std::string generateHeaderBinary (const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a PCD file format.
std::string generateHeaderBinaryCompressed (const pcl::PCLPointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a BINARY_COMPRESSED 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 pcl::PCLPointCloud2 &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 pcl::PCLPointCloud2::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 pcl::PCLPointCloud2 &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 writeBinary (const std::string &file_name, const pcl::PCLPointCloud2 &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 pcl::PCLPointCloud2 &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.
 ~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.

Protected Member Functions

void resetLockingPermissions (const std::string &file_name, boost::interprocess::file_lock &lock)
 Reset permissions for file locking (Boost 1.49+).
void setLockingPermissions (const std::string &file_name, boost::interprocess::file_lock &lock)
 Set permissions for file locking (Boost 1.49+).

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


Constructor & Destructor Documentation

Definition at line 227 of file pcd_io.h.

Definition at line 228 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 74 of file pcd_io.hpp.

std::string pcl::PCDWriter::generateHeaderASCII ( const pcl::PCLPointCloud2 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 1057 of file pcd_io.cpp.

std::string pcl::PCDWriter::generateHeaderBinary ( const pcl::PCLPointCloud2 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 1157 of file pcd_io.cpp.

std::string pcl::PCDWriter::generateHeaderBinaryCompressed ( const pcl::PCLPointCloud2 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 1238 of file pcd_io.cpp.

void pcl::PCDWriter::resetLockingPermissions ( const std::string file_name,
boost::interprocess::file_lock &  lock 
) [protected]

Reset permissions for file locking (Boost 1.49+).

Parameters:
[in]file_namethe file name to reset permission for file locking
[in,out]lockthe file lock

Definition at line 93 of file pcd_io.cpp.

void pcl::PCDWriter::setLockingPermissions ( const std::string file_name,
boost::interprocess::file_lock &  lock 
) [protected]

Set permissions for file locking (Boost 1.49+).

Parameters:
[in]file_namethe file name to set permission for file locking
[in,out]lockthe file lock

Definition at line 69 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 239 of file pcd_io.h.

int pcl::PCDWriter::write ( const std::string file_name,
const pcl::PCLPointCloud2 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 345 of file pcd_io.h.

int pcl::PCDWriter::write ( const std::string file_name,
const pcl::PCLPointCloud2::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 372 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 442 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 467 of file pcd_io.h.

int pcl::PCDWriter::writeASCII ( const std::string file_name,
const pcl::PCLPointCloud2 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 1291 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 460 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 759 of file pcd_io.hpp.

int pcl::PCDWriter::writeBinary ( const std::string file_name,
const pcl::PCLPointCloud2 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 1403 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 126 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 620 of file pcd_io.hpp.

int pcl::PCDWriter::writeBinaryCompressed ( const std::string file_name,
const pcl::PCLPointCloud2 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 1514 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 264 of file pcd_io.hpp.


Member Data Documentation

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

Definition at line 497 of file pcd_io.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:48