Point Cloud Data (PCD) file format reader. More...
#include <pcd_io.h>
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. |
typedef sensor_msgs::PointCloud2 pcl_ros::PCDReader::PointCloud2 |
Reimplemented from pcl_ros::PCLNodelet.
typedef PointCloud2::ConstPtr pcl_ros::PCDReader::PointCloud2ConstPtr |
typedef PointCloud2::Ptr pcl_ros::PCDReader::PointCloud2Ptr |
pcl_ros::PCDReader::PCDReader | ( | ) | [inline] |
double pcl_ros::PCDReader::getPublishRate | ( | ) | [inline] |
std::string pcl_ros::PCDReader::getTFframe | ( | ) | [inline] |
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] |
void pcl_ros::PCDReader::setTFframe | ( | std::string | tf_frame | ) | [inline] |
std::string pcl_ros::PCDReader::file_name_ [protected] |
pcl::PCDReader pcl_ros::PCDReader::impl_ [private] |
PointCloud2Ptr pcl_ros::PCDReader::output_ [protected] |
double pcl_ros::PCDReader::publish_rate_ [protected] |
std::string pcl_ros::PCDReader::tf_frame_ [protected] |