Public Types | Public Member Functions | Public Attributes | Protected Attributes | Private Attributes
pcl_ros::PCDWriter Class Reference

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

#include <pcd_io.h>

Inheritance diagram for pcl_ros::PCDWriter:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

Point Cloud Data (PCD) file format writer.

Author:
Radu Bogdan Rusu

Definition at line 102 of file pcd_io.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_ros::PCDWriter::PointCloud2

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 107 of file pcd_io.h.

typedef PointCloud2::ConstPtr pcl_ros::PCDWriter::PointCloud2ConstPtr

Definition at line 109 of file pcd_io.h.

typedef PointCloud2::Ptr pcl_ros::PCDWriter::PointCloud2Ptr

Definition at line 108 of file pcd_io.h.


Constructor & Destructor Documentation

Definition at line 105 of file pcd_io.h.


Member Function Documentation

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.


Member Data Documentation

Set to true if the output files should be saved in binary mode (true).

Definition at line 122 of file pcd_io.h.

std::string pcl_ros::PCDWriter::file_name_ [protected]

The name of the file that contains the PointCloud data.

Definition at line 119 of file pcd_io.h.

The PCL implementation used.

Definition at line 126 of file pcd_io.h.

The input PointCloud subscriber.

Definition at line 115 of file pcd_io.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Jun 6 2019 21:01:45