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

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

#include <pcd_io.h>

Inheritance diagram for pcl_ros::PCDReader:
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

double getPublishRate ()
 Get the publishing rate in seconds.
std::string getTFframe ()
 Get the TF frame the PointCloud is published in.
virtual void onInit ()
 Nodelet initialization routine. Reads in global parameters used by all nodelets.
 PCDReader ()
 Empty constructor.
void setPublishRate (double publish_rate)
 Set the publishing rate in seconds.
void setTFframe (std::string tf_frame)
 Set the TF frame the PointCloud will be published in.

Protected Attributes

std::string file_name_
 The name of the file that contains the PointCloud data.
PointCloud2Ptr output_
 The output point cloud dataset containing the points loaded from the file.
double publish_rate_
 The publishing interval in seconds. Set to 0 to only publish once (default).
std::string tf_frame_
 The TF frame the data should be published in ("/base_link" by default).

Private Attributes

pcl::PCDReader impl_
 The PCL implementation used.

Detailed Description

Point Cloud Data (PCD) file format reader.

Author:
Radu Bogdan Rusu

Definition at line 50 of file pcd_io.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 pcl_ros::PCDReader::PointCloud2

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 53 of file pcd_io.h.

typedef PointCloud2::ConstPtr pcl_ros::PCDReader::PointCloud2ConstPtr

Definition at line 55 of file pcd_io.h.

typedef PointCloud2::Ptr pcl_ros::PCDReader::PointCloud2Ptr

Definition at line 54 of file pcd_io.h.


Constructor & Destructor Documentation

Empty constructor.

Definition at line 58 of file pcd_io.h.


Member Function Documentation

Get the publishing rate in seconds.

Definition at line 68 of file pcd_io.h.

std::string pcl_ros::PCDReader::getTFframe ( ) [inline]

Get the TF frame the PointCloud is published in.

Definition at line 76 of file pcd_io.h.

void pcl_ros::PCDReader::onInit ( ) [virtual]

Nodelet initialization routine. Reads in global parameters used by all nodelets.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 43 of file pcd_io.cpp.

void pcl_ros::PCDReader::setPublishRate ( double  publish_rate) [inline]

Set the publishing rate in seconds.

Parameters:
publish_ratethe publishing rate in seconds

Definition at line 65 of file pcd_io.h.

void pcl_ros::PCDReader::setTFframe ( std::string  tf_frame) [inline]

Set the TF frame the PointCloud will be published in.

Parameters:
tf_framethe TF frame the PointCloud will be published in

Definition at line 73 of file pcd_io.h.


Member Data Documentation

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

The name of the file that contains the PointCloud data.

Definition at line 86 of file pcd_io.h.

The PCL implementation used.

Definition at line 93 of file pcd_io.h.

The output point cloud dataset containing the points loaded from the file.

Definition at line 89 of file pcd_io.h.

The publishing interval in seconds. Set to 0 to only publish once (default).

Definition at line 80 of file pcd_io.h.

std::string pcl_ros::PCDReader::tf_frame_ [protected]

The TF frame the data should be published in ("/base_link" by default).

Definition at line 83 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 May 5 2016 04:16:43