Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include "jsk_pcl_ros/voxel_grid_downsample_decoder.h"
00036 #include <pluginlib/class_list_macros.h>
00037 #include <pcl/point_types.h>
00038 #include <pcl/filters/passthrough.h>
00039 #include <pcl/filters/voxel_grid.h>
00040 #include <pcl/io/io.h>
00041 #include <pcl_ros/transforms.h>
00042
00043 #include <string>
00044 #include <iostream>
00045 #include <boost/algorithm/string.hpp>
00046 #include <boost/foreach.hpp>
00047 #include <boost/lexical_cast.hpp>
00048
00049
00050 namespace jsk_pcl_ros
00051 {
00052
00053 int VoxelGridDownsampleDecoder::getPointcloudID(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input) {
00054 return input->slice_index;
00055 }
00056
00057 int VoxelGridDownsampleDecoder::getPointcloudSequenceID(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input) {
00058 return input->sequence_id;
00059 }
00060
00061 std::string VoxelGridDownsampleDecoder::getPointcloudFrameId(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input) {
00062 return input->point_cloud.header.frame_id;
00063 }
00064
00065 void VoxelGridDownsampleDecoder::pointCB(const jsk_recognition_msgs::SlicedPointCloudConstPtr &input)
00066 {
00067 NODELET_INFO_STREAM("new pointcloud!" << input->point_cloud.header.frame_id);
00068
00069 int id = getPointcloudID(input);
00070 int new_sequence_id = getPointcloudSequenceID(input);
00071 std::string frame_id = getPointcloudFrameId(input);
00072 if (new_sequence_id != latest_sequence_id_) {
00073 NODELET_INFO_STREAM("clearing pointcloud");
00074 pc_buffer_.clear();
00075 latest_sequence_id_ = new_sequence_id;
00076 }
00077
00078
00079 if (id >= (int)pc_buffer_.size()) {
00080
00081
00082 int extend = id - pc_buffer_.size() + 1;
00083 NODELET_INFO_STREAM("extend " << extend << " pointclouds");
00084 for (int i = 0; i < extend; i++) {
00085 NODELET_INFO_STREAM("new pointcloud allocation!");
00086 pc_buffer_.push_back(jsk_recognition_msgs::SlicedPointCloudConstPtr());
00087 pc_buffer_[pc_buffer_.size() - 1].reset();
00088 }
00089 }
00090
00091 NODELET_INFO_STREAM("id: " << id << " size: " << pc_buffer_.size());
00092 pc_buffer_[id] = input;
00093 if (pc_buffer_.size() == 1) {
00094
00095 }
00096 else {
00097 if (previous_id_ + 1 != id) {
00098 if (previous_id_ != (int)pc_buffer_.size() - 1) {
00099
00100 pc_buffer_.resize(previous_id_ + 1);
00101 }
00102 }
00103 }
00104 previous_id_ = id;
00105
00106 publishBuffer();
00107
00108 }
00109
00110 void VoxelGridDownsampleDecoder::publishBuffer(void)
00111 {
00112 NODELET_INFO("publishBuffer");
00113 if (pc_buffer_.size() == 0 || !pc_buffer_[0]) {
00114 NODELET_WARN("no pointcloud is subscribed yet");
00115 return;
00116 }
00117
00118 std::string result_frame_id = getPointcloudFrameId(pc_buffer_[0]);
00119 pcl::PointCloud<pcl::PointXYZRGB>::Ptr concatenated_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00120 for (size_t i = 0; i < pc_buffer_.size(); i++)
00121 {
00122 if (!pc_buffer_[i]) {
00123 NODELET_INFO_STREAM("buffer[" << i << "] is not yet available, skip it");
00124 continue;
00125 }
00126 pcl::PointCloud<pcl::PointXYZRGB>::Ptr tmp_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00127 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformed_tmp_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00128 fromROSMsg(pc_buffer_[i]->point_cloud, *tmp_cloud);
00129 if (tmp_cloud->points.size() == 0) {
00130 NODELET_INFO_STREAM("buffer[" << i << "] is not yet available, skip it");
00131 continue;
00132 }
00133
00134
00135 tmp_cloud->header.frame_id = getPointcloudFrameId(pc_buffer_[i]);
00136
00137 pcl_ros::transformPointCloud(result_frame_id,
00138 *tmp_cloud,
00139 *transformed_tmp_cloud,
00140 tf_listener);
00141
00142 for (size_t j = 0; j < transformed_tmp_cloud->points.size(); j++) {
00143 concatenated_cloud->points.push_back(transformed_tmp_cloud->points[j]);
00144 }
00145 }
00146 sensor_msgs::PointCloud2 out;
00147 toROSMsg(*concatenated_cloud, out);
00148 out.header = pc_buffer_[0]->point_cloud.header;
00149 out.header.frame_id = getPointcloudFrameId(pc_buffer_[0]);
00150 pub_.publish(out);
00151 }
00152
00153 void VoxelGridDownsampleDecoder::onInit(void)
00154 {
00155 ConnectionBasedNodelet::onInit();
00156 previous_id_ = -1;
00157
00158 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00159 onInitPostProcess();
00160 }
00161
00162 void VoxelGridDownsampleDecoder::subscribe()
00163 {
00164 sub_ = pnh_->subscribe("input", 1, &VoxelGridDownsampleDecoder::pointCB,
00165 this);
00166 }
00167
00168 void VoxelGridDownsampleDecoder::unsubscribe()
00169 {
00170 sub_.shutdown();
00171 }
00172 }
00173
00174
00175 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::VoxelGridDownsampleDecoder,
00176 nodelet::Nodelet);