37 #ifndef JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_ 38 #define JSK_PCL_ROS_POINTCLOUD_DATABASE_SERVER_H_ 41 #include <dynamic_reconfigure/server.h> 42 #include <sensor_msgs/PointCloud2.h> 43 #include <pcl/PolygonMesh.h> 44 #include <jsk_recognition_msgs/PointsArray.h> 45 #include "jsk_pcl_ros/PointcloudDatabaseServerConfig.h" 55 virtual pcl::PointCloud<pcl::PointXYZRGB>::Ptr
57 virtual sensor_msgs::PointCloud2
65 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud_;
73 typedef jsk_pcl_ros::PointcloudDatabaseServerConfig
Config;
75 virtual void onInit();
77 virtual void configCallback(Config &config, uint32_t level);
const std::string file_name_
jsk_recognition_msgs::PointsArray array_msg_
ros::Publisher pub_cloud_
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getPointCloud()
virtual ~PointCloudData()
boost::shared_ptr< PointCloudData > Ptr
std::vector< std::string > files_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual sensor_msgs::PointCloud2 getROSPointCloud(ros::Time stamp)
sensor_msgs::PointCloud2 point_msg_
jsk_pcl_ros::PointcloudDatabaseServerConfig Config
std::vector< PointCloudData::Ptr > point_clouds_
boost::mutex mutex
global mutex.
ros::Publisher pub_points_array_
PointCloudData(const std::string fname)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_