Go to the documentation of this file.
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
63 pcl::PolygonMesh
mesh_;
65 pcl::PointCloud<pcl::PointXYZRGB>::Ptr
cloud_;
73 typedef jsk_pcl_ros::PointcloudDatabaseServerConfig
Config;
78 std::vector<std::string>
files_;
jsk_recognition_msgs::PointsArray array_msg_
virtual ~PointcloudDatabaseServer()
boost::shared_ptr< PointCloudData > Ptr
ros::Publisher pub_cloud_
virtual ~PointCloudData()
std::vector< std::string > files_
virtual void timerCallback(const ros::TimerEvent &event)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::PointCloud2 point_msg_
virtual pcl::PointCloud< pcl::PointXYZRGB >::Ptr getPointCloud()
jsk_pcl_ros::PointcloudDatabaseServerConfig Config
std::vector< PointCloudData::Ptr > point_clouds_
PointCloudData(const std::string fname)
pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud_
const std::string file_name_
virtual sensor_msgs::PointCloud2 getROSPointCloud(ros::Time stamp)
boost::mutex mutex
global mutex.
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_points_array_
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45