grid_sampler_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 #include "jsk_pcl_ros/grid_sampler.h"
00036 #include "jsk_pcl_ros/pcl_conversion_util.h"
00037 #include <pcl/common/common.h>
00038 
00039 #include <pluginlib/class_list_macros.h>
00040 
00041 namespace jsk_pcl_ros
00042 {
00043   void GridSampler::onInit()
00044   {
00045     ConnectionBasedNodelet::onInit();
00046     pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output", 1);
00047     dynamic_reconfigure::Server<Config>::CallbackType f =
00048       boost::bind (&GridSampler::configCallback, this, _1, _2);
00049     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00050     srv_->setCallback (f);
00051     
00052   }
00053 
00054   void GridSampler::subscribe()
00055   {
00056     sub_ = pnh_->subscribe("input", 1, &GridSampler::sample, this);
00057   }
00058   
00059   void GridSampler::unsubscribe()
00060   {
00061     sub_.shutdown();
00062   }
00063   
00064   void GridSampler::configCallback(Config &config, uint32_t level)
00065   {
00066     boost::mutex::scoped_lock(mutex_);
00067     if (config.grid_size == 0.0) {
00068       JSK_NODELET_WARN("grid_size == 0.0 is prohibited");
00069       return;
00070     }
00071     else {
00072       grid_size_ = config.grid_size;
00073       min_indices_ = config.min_indices;
00074     }
00075   }
00076 
00077   void GridSampler::sample(const sensor_msgs::PointCloud2::ConstPtr& msg)
00078   {
00079     boost::mutex::scoped_lock(mutex_);
00080     pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
00081     pcl::fromROSMsg(*msg, *pcl_cloud);
00082     Eigen::Vector4f minpt, maxpt;
00083     pcl::getMinMax3D<pcl::PointXYZRGB>(*pcl_cloud, minpt, maxpt);
00084     int x_bin_num = ceil((maxpt[0] - minpt[0]) / grid_size_);
00085     int y_bin_num = ceil((maxpt[1] - minpt[1]) / grid_size_);
00086     int z_bin_num = ceil((maxpt[2] - minpt[2]) / grid_size_);
00087 
00088     //        x             y             z
00089     std::map<int, std::map<int, std::map<int, std::vector<size_t > > > > grid;
00090     for (size_t i = 0; i < pcl_cloud->points.size(); i++) {
00091       pcl::PointXYZRGB point = pcl_cloud->points[i];
00092       if (isnan(point.x) || isnan(point.y) || isnan(point.z)) {
00093         // skip nan
00094         continue;
00095       }
00096       int xbin = int((point.x - minpt[0]) / grid_size_);
00097       int ybin = int((point.y - minpt[1]) / grid_size_);
00098       int zbin = int((point.z - minpt[2]) / grid_size_);
00099       std::map<int, std::map<int, std::map<int, std::vector<size_t> > > >::iterator xit
00100         = grid.find(xbin);
00101       if (xit == grid.end()) {  // cannot find x bin
00102         JSK_NODELET_DEBUG_STREAM("no x bin" << xbin);
00103         std::map<int, std::vector<size_t> > new_z;
00104         std::vector<size_t> new_indices;
00105         new_indices.push_back(i);
00106         new_z[zbin] = new_indices;
00107         std::map<int, std::map<int, std::vector<size_t> > > new_y;
00108         new_y[ybin] = new_z;
00109         grid[xbin] = new_y;
00110       }
00111       else {
00112         JSK_NODELET_DEBUG_STREAM("found x bin" << xbin);
00113         std::map<int, std::map<int, std::vector<size_t> > > ybins = xit->second;
00114         std::map<int, std::map<int, std::vector<size_t> > >::iterator yit
00115           = ybins.find(ybin);
00116         if (yit == ybins.end()) { // cannot find y bin
00117           JSK_NODELET_DEBUG_STREAM("no y bin" << ybin);
00118           std::map<int, std::vector<size_t> > new_z;
00119           std::vector<size_t> new_indices;
00120           new_indices.push_back(i);
00121           new_z[zbin] = new_indices;
00122           xit->second[ybin] = new_z;
00123         }
00124         else {
00125           JSK_NODELET_DEBUG_STREAM("found y bin" << ybin);
00126           std::map<int, std::vector<size_t> > zbins = yit->second;
00127           std::map<int, std::vector<size_t> >::iterator zit
00128             = zbins.find(zbin);
00129           if (zit == zbins.end()) {
00130             JSK_NODELET_DEBUG_STREAM("no z bin" << zbin);
00131             std::vector<size_t> new_indices;
00132             new_indices.push_back(i);
00133             xit->second[ybin][zbin] = new_indices;
00134           }
00135           else {
00136             JSK_NODELET_DEBUG_STREAM("found z bin" << zbin);
00137             xit->second[ybin][zbin].push_back(i);
00138           }
00139         }
00140       }
00141     }
00142     // publish the result
00143     jsk_recognition_msgs::ClusterPointIndices output;
00144     output.header = msg->header;
00145     for (std::map<int, std::map<int, std::map<int, std::vector<size_t> > > >::iterator xit = grid.begin();
00146          xit != grid.end();
00147          xit++) {
00148       std::map<int, std::map<int, std::vector<size_t> > > ybins = xit->second;
00149       for (std::map<int, std::map<int, std::vector<size_t> > >::iterator yit = ybins.begin();
00150            yit != ybins.end();
00151            yit++) {
00152         std::map<int, std::vector<size_t> > zbins = yit->second;
00153         for (std::map<int, std::vector<size_t> >::iterator zit = zbins.begin();
00154              zit != zbins.end();
00155              zit++) {
00156           std::vector<size_t> indices = zit->second;
00157           JSK_NODELET_DEBUG_STREAM("size: " << indices.size());
00158           if (indices.size() > min_indices_) {
00159             PCLIndicesMsg ros_indices;
00160             ros_indices.header = msg->header;
00161             for (size_t j = 0; j < indices.size(); j++) {
00162               ros_indices.indices.push_back(indices[j]);
00163             }
00164             output.cluster_indices.push_back(ros_indices);
00165           }
00166         }
00167       }
00168     }
00169     pub_.publish(output);
00170   }
00171 }
00172 
00173 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::GridSampler, nodelet::Nodelet);
00174 


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47