#include <pointcloud_database_server.h>
| Public Types | |
| typedef boost::shared_ptr < PointCloudData > | Ptr | 
| Public Member Functions | |
| virtual pcl::PointCloud < pcl::PointXYZRGB >::Ptr | getPointCloud () | 
| virtual sensor_msgs::PointCloud2 | getROSPointCloud (ros::Time stamp) | 
| PointCloudData (const std::string fname) | |
| virtual | ~PointCloudData () | 
| Protected Attributes | |
| pcl::PointCloud < pcl::PointXYZRGB >::Ptr | cloud_ | 
| std::string | ext_ | 
| const std::string | file_name_ | 
| pcl::PolygonMesh | mesh_ | 
| std::string | stem_ | 
Definition at line 49 of file pointcloud_database_server.h.
| typedef boost::shared_ptr<PointCloudData> jsk_pcl_ros::PointCloudData::Ptr | 
Definition at line 52 of file pointcloud_database_server.h.
| jsk_pcl_ros::PointCloudData::PointCloudData | ( | const std::string | fname | ) | 
Definition at line 46 of file pointcloud_database_server_nodelet.cpp.
| virtual jsk_pcl_ros::PointCloudData::~PointCloudData | ( | ) |  [inline, virtual] | 
Definition at line 54 of file pointcloud_database_server.h.
| pcl::PointCloud< pcl::PointXYZRGB >::Ptr jsk_pcl_ros::PointCloudData::getPointCloud | ( | ) |  [virtual] | 
Definition at line 64 of file pointcloud_database_server_nodelet.cpp.
| sensor_msgs::PointCloud2 jsk_pcl_ros::PointCloudData::getROSPointCloud | ( | ros::Time | stamp | ) |  [virtual] | 
Definition at line 70 of file pointcloud_database_server_nodelet.cpp.
| pcl::PointCloud<pcl::PointXYZRGB>::Ptr jsk_pcl_ros::PointCloudData::cloud_  [protected] | 
Definition at line 65 of file pointcloud_database_server.h.
| std::string jsk_pcl_ros::PointCloudData::ext_  [protected] | 
Definition at line 62 of file pointcloud_database_server.h.
| const std::string jsk_pcl_ros::PointCloudData::file_name_  [protected] | 
Definition at line 61 of file pointcloud_database_server.h.
| pcl::PolygonMesh jsk_pcl_ros::PointCloudData::mesh_  [protected] | 
Definition at line 63 of file pointcloud_database_server.h.
| std::string jsk_pcl_ros::PointCloudData::stem_  [protected] | 
Definition at line 64 of file pointcloud_database_server.h.