pcl::PCDWriter Class Reference

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

#include <pcd_io.h>

List of all members.

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 v.7 file format.
std::string generateHeaderBinary (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation)
 Generate the header of a PCD v.7 file format.
template<typename PointT >
int write (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, 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(), 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 &cloud, const Eigen::Vector4f &origin=Eigen::Vector4f::Zero(), const Eigen::Quaternionf &orientation=Eigen::Quaternionf::Identity(), 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(), int precision=7)
 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.

Detailed Description

Point Cloud Data (PCD) file format writer.

Author:
Radu Bogdan Rusu

Definition at line 146 of file pcd_io.h.


Member Function Documentation

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

Generate the header of a PCD v.7 file format.

Parameters:
cloud the point cloud data message
origin the sensor acquisition origin
orientation the sensor acquisition orientation

Definition at line 550 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 v.7 file format.

Parameters:
cloud the point cloud data message
origin the sensor acquisition origin
orientation the sensor acquisition orientation

Definition at line 596 of file pcd_io.cpp.

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

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

Parameters:
file_name the output file name
cloud the pcl::PointCloud data
binary set to true if the file is to be written in a binary PCD format, false (default) for ASCII

Definition at line 229 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 (),
bool  binary = 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 (boost shared pointer)
binary set to true if the file is to be written in a binary PCD format, false (default) for ASCII
origin the sensor acquisition origin
orientation the sensor acquisition orientation

Definition at line 215 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 (),
bool  binary = 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 set to true if the file is to be written in a binary PCD format, false (default) for ASCII

Definition at line 196 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 (),
int  precision = 7 
)

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

Parameters:
file_name the output file name
cloud the point cloud data message
origin the sensor acquisition origin
orientation the sensor acquisition orientation
precision the specified output numeric stream precision (default: 7)

Definition at line 675 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:
file_name the output file name
cloud the point cloud data message
origin the sensor acquisition origin
orientation the sensor acquisition orientation

Definition at line 781 of file pcd_io.cpp.


The documentation for this class was generated from the following files:
 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:20 2013