#include <pointcloud_database_server.h>

| Public Types | |
| typedef jsk_pcl_ros::PointcloudDatabaseServerConfig | Config | 
| Public Member Functions | |
| virtual | ~PointcloudDatabaseServer () | 
| Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) | 
| virtual void | onInit () | 
| virtual void | timerCallback (const ros::TimerEvent &event) | 
| Protected Attributes | |
| jsk_recognition_msgs::PointsArray | array_msg_ | 
| double | duration_ | 
| std::vector< std::string > | files_ | 
| boost::mutex | mutex_ | 
| std::vector< PointCloudData::Ptr > | point_clouds_ | 
| sensor_msgs::PointCloud2 | point_msg_ | 
| ros::Publisher | pub_cloud_ | 
| ros::Publisher | pub_points_array_ | 
| boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ | 
| ros::Timer | timer_ | 
| bool | use_array_ | 
Definition at line 69 of file pointcloud_database_server.h.
| typedef jsk_pcl_ros::PointcloudDatabaseServerConfig jsk_pcl_ros::PointcloudDatabaseServer::Config | 
Definition at line 73 of file pointcloud_database_server.h.
Definition at line 79 of file pointcloud_database_server_nodelet.cpp.
| void jsk_pcl_ros::PointcloudDatabaseServer::configCallback | ( | Config & | config, | 
| uint32_t | level | ||
| ) |  [protected, virtual] | 
Definition at line 123 of file pointcloud_database_server_nodelet.cpp.
| void jsk_pcl_ros::PointcloudDatabaseServer::onInit | ( | void | ) |  [protected, virtual] | 
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 84 of file pointcloud_database_server_nodelet.cpp.
| void jsk_pcl_ros::PointcloudDatabaseServer::timerCallback | ( | const ros::TimerEvent & | event | ) |  [protected, virtual] | 
Definition at line 108 of file pointcloud_database_server_nodelet.cpp.
| jsk_recognition_msgs::PointsArray jsk_pcl_ros::PointcloudDatabaseServer::array_msg_  [protected] | 
Definition at line 88 of file pointcloud_database_server.h.
| double jsk_pcl_ros::PointcloudDatabaseServer::duration_  [protected] | 
Definition at line 91 of file pointcloud_database_server.h.
Definition at line 78 of file pointcloud_database_server.h.
Definition at line 83 of file pointcloud_database_server.h.
Definition at line 87 of file pointcloud_database_server.h.
| sensor_msgs::PointCloud2 jsk_pcl_ros::PointcloudDatabaseServer::point_msg_  [protected] | 
Definition at line 89 of file pointcloud_database_server.h.
Definition at line 85 of file pointcloud_database_server.h.
Definition at line 84 of file pointcloud_database_server.h.
| boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PointcloudDatabaseServer::srv_  [protected] | 
Definition at line 82 of file pointcloud_database_server.h.
Definition at line 86 of file pointcloud_database_server.h.
| bool jsk_pcl_ros::PointcloudDatabaseServer::use_array_  [protected] | 
Definition at line 92 of file pointcloud_database_server.h.