Public Member Functions | Public Attributes | Protected Attributes | Private Attributes | List of all members
PointCloudToPCD Class Reference

Public Member Functions

void cloud_cb (const pcl::PCLPointCloud2::ConstPtr &cloud)
 
 PointCloudToPCD ()
 

Public Attributes

string cloud_topic_
 
ros::Subscriber sub_
 

Protected Attributes

ros::NodeHandle nh_
 

Private Attributes

bool binary_
 
bool compressed_
 
std::string fixed_frame_
 
std::string prefix_
 
tf2_ros::Buffer tf_buffer_
 
tf2_ros::TransformListener tf_listener_
 

Detailed Description

Author
Radu Bogdan Rusu

pointcloud_to_pcd is a simple node that retrieves a ROS point cloud message and saves it to disk into a PCD (Point Cloud Data) file format.

Definition at line 65 of file pointcloud_to_pcd.cpp.

Constructor & Destructor Documentation

PointCloudToPCD::PointCloudToPCD ( )
inline

Definition at line 135 of file pointcloud_to_pcd.cpp.

Member Function Documentation

void PointCloudToPCD::cloud_cb ( const pcl::PCLPointCloud2::ConstPtr &  cloud)
inline

Definition at line 86 of file pointcloud_to_pcd.cpp.

Member Data Documentation

bool PointCloudToPCD::binary_
private

Definition at line 72 of file pointcloud_to_pcd.cpp.

string PointCloudToPCD::cloud_topic_

Definition at line 79 of file pointcloud_to_pcd.cpp.

bool PointCloudToPCD::compressed_
private

Definition at line 73 of file pointcloud_to_pcd.cpp.

std::string PointCloudToPCD::fixed_frame_
private

Definition at line 74 of file pointcloud_to_pcd.cpp.

ros::NodeHandle PointCloudToPCD::nh_
protected

Definition at line 68 of file pointcloud_to_pcd.cpp.

std::string PointCloudToPCD::prefix_
private

Definition at line 71 of file pointcloud_to_pcd.cpp.

ros::Subscriber PointCloudToPCD::sub_

Definition at line 81 of file pointcloud_to_pcd.cpp.

tf2_ros::Buffer PointCloudToPCD::tf_buffer_
private

Definition at line 75 of file pointcloud_to_pcd.cpp.

tf2_ros::TransformListener PointCloudToPCD::tf_listener_
private

Definition at line 76 of file pointcloud_to_pcd.cpp.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:53