Point Cloud Data (PLY) file format writer. More...
#include <ply_io.h>
Public Member Functions | |
std::string | generateHeaderASCII (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, int valid_points, bool use_camera=true) |
Generate the header of a PLY v.7 file format. | |
std::string | generateHeaderBinary (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, int valid_points, bool use_camera=true) |
Generate the header of a PLY v.7 file format. | |
PLYWriter () | |
Constructor. | |
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 PLY 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, bool use_camera=true) |
Save point cloud data to a PLY 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, bool use_camera=true) |
Save point cloud data to a PLY file containing n-D points. | |
template<typename PointT > | |
int | write (const std::string &file_name, const pcl::PointCloud< PointT > &cloud, bool binary=false, bool use_camera=true) |
Save point cloud data to a PLY 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=8, bool use_camera=true) |
Save point cloud data to a PLY 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 PLY file containing n-D points, in BINARY format. | |
~PLYWriter () | |
Destructor. | |
Private Member Functions | |
std::string | generateHeader (const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, bool binary, bool use_camera, int valid_points) |
Generate a PLY header. | |
void | writeContentWithCameraASCII (int nr_points, int point_size, const sensor_msgs::PointCloud2 &cloud, const Eigen::Vector4f &origin, const Eigen::Quaternionf &orientation, std::ofstream &fs) |
void | writeContentWithRangeGridASCII (int nr_points, int point_size, const sensor_msgs::PointCloud2 &cloud, std::ostringstream &fs, int &nb_valid_points) |
pcl::PLYWriter::PLYWriter | ( | ) | [inline] |
pcl::PLYWriter::~PLYWriter | ( | ) | [inline] |
std::string pcl::PLYWriter::generateHeader | ( | const sensor_msgs::PointCloud2 & | cloud, |
const Eigen::Vector4f & | origin, | ||
const Eigen::Quaternionf & | orientation, | ||
bool | binary, | ||
bool | use_camera, | ||
int | valid_points | ||
) | [private] |
Generate a PLY header.
[in] | cloud | the input point cloud |
[in] | binary | whether the PLY file should be saved as binary data (true) or ascii (false) |
Definition at line 453 of file ply_io.cpp.
std::string pcl::PLYWriter::generateHeaderASCII | ( | const sensor_msgs::PointCloud2 & | cloud, |
const Eigen::Vector4f & | origin, | ||
const Eigen::Quaternionf & | orientation, | ||
int | valid_points, | ||
bool | use_camera = true |
||
) | [inline] |
Generate the header of a PLY v.7 file format.
[in] | cloud | the point cloud data message |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
[in] | valid_points | number of valid points (finite ones for range_grid and all of them for camer) |
[in] | use_camera | if set to true then PLY file will use element camera else element range_grid will be used. |
std::string pcl::PLYWriter::generateHeaderBinary | ( | const sensor_msgs::PointCloud2 & | cloud, |
const Eigen::Vector4f & | origin, | ||
const Eigen::Quaternionf & | orientation, | ||
int | valid_points, | ||
bool | use_camera = true |
||
) | [inline] |
Generate the header of a PLY v.7 file format.
[in] | cloud | the point cloud data message |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
[in] | valid_points | number of valid points (finite ones for range_grid and all of them for camer) |
[in] | use_camera | if set to true then PLY file will use element camera else element range_grid will be used. |
int pcl::PLYWriter::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 PLY file containing n-D points.
[in] | file_name | the output file name |
[in] | cloud | the point cloud data message |
[in] | origin | the sensor acquisition origin |
[in] | orientation | the sensor acquisition orientation |
[in] | binary | set to true if the file is to be written in a binary PLY format, false (default) for ASCII |
Implements pcl::FileWriter.
int pcl::PLYWriter::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 , |
||
bool | use_camera = true |
||
) | [inline] |
Save point cloud data to a PLY file containing n-D points.
[in] | file_name | the output file name |
[in] | cloud | the point cloud data message |
[in] | origin | the sensor acquisition origin |
[in] | orientation | the sensor acquisition orientation |
[in] | binary | set to true if the file is to be written in a binary PLY format, false (default) for ASCII |
[in] | use_camera | set to true to used camera element and false to use range_grid element |
int pcl::PLYWriter::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 , |
||
bool | use_camera = true |
||
) | [inline] |
Save point cloud data to a PLY file containing n-D points.
[in] | file_name | the output file name |
[in] | cloud | the point cloud data message (boost shared pointer) |
[in] | origin | the sensor acquisition origin |
[in] | orientation | the sensor acquisition orientation |
[in] | binary | set to true if the file is to be written in a binary PLY format, false (default) for ASCII |
[in] | use_camera | set to true to used camera element and false to use range_grid element |
int pcl::PLYWriter::write | ( | const std::string & | file_name, |
const pcl::PointCloud< PointT > & | cloud, | ||
bool | binary = false , |
||
bool | use_camera = true |
||
) | [inline] |
Save point cloud data to a PLY file containing n-D points.
[in] | file_name | the output file name |
[in] | cloud | the pcl::PointCloud data |
[in] | binary | set to true if the file is to be written in a binary PLY format, false (default) for ASCII |
[in] | use_camera | set to true to used camera element and false to use range_grid element |
int pcl::PLYWriter::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 = 8 , |
||
bool | use_camera = true |
||
) |
Save point cloud data to a PLY file containing n-D points, in ASCII format.
[in] | file_name | the output file name |
[in] | cloud | the point cloud data message |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
[in] | precision | the specified output numeric stream precision (default: 8) |
[in] | use_camera | if set to true then PLY file will use element camera else element range_grid will be used. |
Definition at line 601 of file ply_io.cpp.
int pcl::PLYWriter::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 PLY file containing n-D points, in BINARY format.
[in] | file_name | the output file name |
[in] | cloud | the point cloud data message |
[in] | origin | the sensor data acquisition origin (translation) |
[in] | orientation | the sensor data acquisition origin (rotation) |
Definition at line 944 of file ply_io.cpp.
void pcl::PLYWriter::writeContentWithCameraASCII | ( | int | nr_points, |
int | point_size, | ||
const sensor_msgs::PointCloud2 & | cloud, | ||
const Eigen::Vector4f & | origin, | ||
const Eigen::Quaternionf & | orientation, | ||
std::ofstream & | fs | ||
) | [private] |
Definition at line 648 of file ply_io.cpp.
void pcl::PLYWriter::writeContentWithRangeGridASCII | ( | int | nr_points, |
int | point_size, | ||
const sensor_msgs::PointCloud2 & | cloud, | ||
std::ostringstream & | fs, | ||
int & | nb_valid_points | ||
) | [private] |
Definition at line 794 of file ply_io.cpp.