Point Cloud Data (PCD) file format writer. More...
#include <pcd_io.h>
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. | |
Point Cloud Data (PCD) file format writer.
Definition at line 146 of file pcd_io.h.
| 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.
| 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.
| 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.
| 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.
| 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 |
| 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.
| 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 |
| 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.
| 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 |
| 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.
| 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.
| 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.