36 #ifndef JSK_PCL_ROS_VOXEL_GRID_DOWNSAMPLE_DECODER_H_ 37 #define JSK_PCL_ROS_VOXEL_GRID_DOWNSAMPLE_DECODER_H_ 42 #include <sensor_msgs/PointCloud2.h> 43 #include <visualization_msgs/Marker.h> 44 #include "jsk_recognition_msgs/SlicedPointCloud.h" 47 #include <pcl/point_types.h> 59 int getPointcloudID(
const jsk_recognition_msgs::SlicedPointCloudConstPtr &input);
68 std::vector<jsk_recognition_msgs::SlicedPointCloudConstPtr>
pc_buffer_;
69 void pointCB(
const jsk_recognition_msgs::SlicedPointCloudConstPtr &input);
76 #endif // JSK_PCL_ROS_VOXEL_GRID_DOWNSAMPLE_MANAGER_H
int getPointcloudSequenceID(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input)
int getPointcloudID(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input)
std::string getPointcloudFrameId(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input)
std::vector< jsk_recognition_msgs::SlicedPointCloudConstPtr > pc_buffer_
void pointCB(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input)
tf::TransformListener tf_listener
virtual void unsubscribe()