pcl_ros::PCDReader Class Reference
Point Cloud Data (PCD) file format reader.
More...
#include <pcd_io.h>
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 47 of file pcd_io.h.
Member Typedef Documentation
Constructor & Destructor Documentation
pcl_ros::PCDReader::PCDReader |
( |
|
) |
[inline] |
Empty constructor.
Definition at line 49 of file pcd_io.h.
Member Function Documentation
double pcl_ros::PCDReader::getPublishRate |
( |
|
) |
[inline] |
Get the publishing rate in seconds.
Definition at line 59 of file pcd_io.h.
std::string pcl_ros::PCDReader::getTFframe |
( |
|
) |
[inline] |
Get the TF frame the PointCloud is published in.
Definition at line 67 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_rate | the publishing rate in seconds |
Definition at line 56 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_frame | the TF frame the PointCloud will be published in |
Definition at line 64 of file pcd_io.h.
Member Data Documentation
The name of the file that contains the PointCloud data.
Definition at line 77 of file pcd_io.h.
The PCL implementation used.
Definition at line 84 of file pcd_io.h.
The output point cloud dataset containing the points loaded from the file.
Definition at line 80 of file pcd_io.h.
The publishing interval in seconds. Set to 0 to only publish once (default).
Definition at line 71 of file pcd_io.h.
The TF frame the data should be published in ("/base_link" by default).
Definition at line 74 of file pcd_io.h.
The documentation for this class was generated from the following files: