Point Cloud Data (PCD) file format writer. More...
#include <pcd_io.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
Public Member Functions | |
void | input_callback (const PointCloud2ConstPtr &cloud) |
virtual void | onInit () |
Nodelet initialization routine. Reads in global parameters used by all nodelets. | |
PCDWriter () | |
Public Attributes | |
ros::Subscriber | sub_input_ |
The input PointCloud subscriber. | |
Protected Attributes | |
bool | binary_mode_ |
Set to true if the output files should be saved in binary mode (true). | |
std::string | file_name_ |
The name of the file that contains the PointCloud data. | |
Private Attributes | |
pcl::PCDWriter | impl_ |
The PCL implementation used. |
typedef sensor_msgs::PointCloud2 pcl_ros::PCDWriter::PointCloud2 |
Reimplemented from pcl_ros::PCLNodelet.
typedef PointCloud2::ConstPtr pcl_ros::PCDWriter::PointCloud2ConstPtr |
typedef PointCloud2::Ptr pcl_ros::PCDWriter::PointCloud2Ptr |
pcl_ros::PCDWriter::PCDWriter | ( | ) | [inline] |
void pcl_ros::PCDWriter::input_callback | ( | const PointCloud2ConstPtr & | cloud | ) |
Definition at line 152 of file pcd_io.cpp.
void pcl_ros::PCDWriter::onInit | ( | ) | [virtual] |
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 134 of file pcd_io.cpp.
bool pcl_ros::PCDWriter::binary_mode_ [protected] |
std::string pcl_ros::PCDWriter::file_name_ [protected] |
pcl::PCDWriter pcl_ros::PCDWriter::impl_ [private] |