voxel_grid_large_scale_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros/voxel_grid_large_scale.h"
00039 #include <pcl/common/common.h>
00040 #include <pcl/common/io.h>
00041 #include <pcl/filters/voxel_grid.h>
00042 #include <pcl/filters/crop_box.h>
00043 #include <jsk_recognition_utils/pcl_conversion_util.h>
00044 
00045 namespace jsk_pcl_ros
00046 {
00047   void VoxelGridLargeScale::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00052       boost::bind(&VoxelGridLargeScale::configCallback, this, _1, _2);
00053     srv_->setCallback(f);
00054     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00055     onInitPostProcess();
00056   }
00057 
00058   void VoxelGridLargeScale::subscribe()
00059   {
00060     sub_ = pnh_->subscribe("input", 1, &VoxelGridLargeScale::filter, this);
00061   }
00062 
00063   void VoxelGridLargeScale::unsubscribe()
00064   {
00065     sub_.shutdown();
00066   }
00067   
00068   void VoxelGridLargeScale::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
00069   {
00070     boost::mutex::scoped_lock lock(mutex_);
00071     if (leaf_size_ == 0.0) {
00072       pub_.publish(msg);
00073     }
00074     else {
00075       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00076       pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
00077       pcl::fromROSMsg(*msg, *cloud);
00078       // check size
00079       Eigen::Vector4f min_pt, max_pt;
00080       pcl::getMinMax3D(*cloud, min_pt, max_pt);
00081       Eigen::Vector4f diff_pt = max_pt - min_pt;
00082       const int32_t int_max = std::numeric_limits<int32_t>::max();
00083       const int64_t dx = static_cast<int64_t>(diff_pt[0] / leaf_size_) + 1;
00084       const int64_t dy = static_cast<int64_t>(diff_pt[1] / leaf_size_) + 1;
00085       const int64_t dz = static_cast<int64_t>(diff_pt[2] / leaf_size_) + 1;
00086       const int min_dx = int_max / (dy * dz);
00087       const int num_x = dx / min_dx + 1;
00088       const double box_size = min_dx * leaf_size_;
00089       // ROS_INFO("num_x: %d", num_x);
00090       // ROS_INFO("%d, %d, %d", dx, dy, dz);
00091       // ROS_INFO("%d, %d, %d", min_dx, dx, dy*dz);
00092       for (int xi = 0; xi < num_x; xi++) {
00093         Eigen::Vector4f min_box = min_pt + Eigen::Vector4f(box_size * xi,
00094                                                            0,
00095                                                            0,
00096                                                            0);
00097         Eigen::Vector4f max_box = min_pt + Eigen::Vector4f(box_size * (xi + 1),
00098                                                            diff_pt[1],
00099                                                            diff_pt[2],
00100                                                            0);
00101         pcl::CropBox<pcl::PointXYZ> crop_box;
00102         crop_box.setMin(min_box);
00103         crop_box.setMax(max_box);
00104         crop_box.setInputCloud(cloud);
00105         pcl::PointCloud<pcl::PointXYZ>::Ptr box_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00106         crop_box.filter(*box_cloud);
00107         pcl::VoxelGrid<pcl::PointXYZ> voxel;
00108         voxel.setLeafSize(leaf_size_, leaf_size_, leaf_size_);
00109         voxel.setInputCloud(box_cloud);
00110         pcl::PointCloud<pcl::PointXYZ>::Ptr voxel_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00111         voxel.filter(*voxel_cloud);
00112         *output += *voxel_cloud;
00113       }
00114       sensor_msgs::PointCloud2 ros_cloud;
00115       pcl::toROSMsg(*output, ros_cloud);
00116       ros_cloud.header = msg->header;
00117       pub_.publish(ros_cloud);
00118     }
00119   }
00120 
00121   void VoxelGridLargeScale::configCallback(Config& config, uint32_t level)
00122   {
00123     boost::mutex::scoped_lock lock(mutex_);
00124     leaf_size_ = config.leaf_size;
00125   }
00126 }
00127 #include <pluginlib/class_list_macros.h>
00128 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::VoxelGridLargeScale,
00129                         nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50