voxel_grid_large_scale_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #define BOOST_PARAMETER_MAX_ARITY 7
37 
39 #include <pcl/common/common.h>
40 #include <pcl/common/io.h>
41 #include <pcl/filters/voxel_grid.h>
42 #include <pcl/filters/crop_box.h>
44 
45 namespace jsk_pcl_ros
46 {
48  {
49  DiagnosticNodelet::onInit();
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  typename dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind(&VoxelGridLargeScale::configCallback, this, _1, _2);
53  srv_->setCallback(f);
54  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
56  }
57 
59  {
60  sub_ = pnh_->subscribe("input", 1, &VoxelGridLargeScale::filter, this);
61  }
62 
64  {
65  sub_.shutdown();
66  }
67 
68  void VoxelGridLargeScale::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
69  {
70  boost::mutex::scoped_lock lock(mutex_);
71  if (leaf_size_ == 0.0) {
72  pub_.publish(msg);
73  }
74  else {
75  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
76  pcl::PointCloud<pcl::PointXYZ>::Ptr output(new pcl::PointCloud<pcl::PointXYZ>);
77  pcl::fromROSMsg(*msg, *cloud);
78  // check size
79  Eigen::Vector4f min_pt, max_pt;
80  pcl::getMinMax3D(*cloud, min_pt, max_pt);
81  Eigen::Vector4f diff_pt = max_pt - min_pt;
82  const int32_t int_max = std::numeric_limits<int32_t>::max();
83  const int64_t dx = static_cast<int64_t>(diff_pt[0] / leaf_size_) + 1;
84  const int64_t dy = static_cast<int64_t>(diff_pt[1] / leaf_size_) + 1;
85  const int64_t dz = static_cast<int64_t>(diff_pt[2] / leaf_size_) + 1;
86  const int min_dx = int_max / (dy * dz);
87  const int num_x = dx / min_dx + 1;
88  const double box_size = min_dx * leaf_size_;
89  // ROS_INFO("num_x: %d", num_x);
90  // ROS_INFO("%d, %d, %d", dx, dy, dz);
91  // ROS_INFO("%d, %d, %d", min_dx, dx, dy*dz);
92  for (int xi = 0; xi < num_x; xi++) {
93  Eigen::Vector4f min_box = min_pt + Eigen::Vector4f(box_size * xi,
94  0,
95  0,
96  0);
97  Eigen::Vector4f max_box = min_pt + Eigen::Vector4f(box_size * (xi + 1),
98  diff_pt[1],
99  diff_pt[2],
100  0);
101  pcl::CropBox<pcl::PointXYZ> crop_box;
102  crop_box.setMin(min_box);
103  crop_box.setMax(max_box);
104  crop_box.setInputCloud(cloud);
105  pcl::PointCloud<pcl::PointXYZ>::Ptr box_cloud(new pcl::PointCloud<pcl::PointXYZ>);
106  crop_box.filter(*box_cloud);
107  pcl::VoxelGrid<pcl::PointXYZ> voxel;
108  voxel.setLeafSize(leaf_size_, leaf_size_, leaf_size_);
109  voxel.setInputCloud(box_cloud);
110  pcl::PointCloud<pcl::PointXYZ>::Ptr voxel_cloud(new pcl::PointCloud<pcl::PointXYZ>);
111  voxel.filter(*voxel_cloud);
112  *output += *voxel_cloud;
113  }
114  sensor_msgs::PointCloud2 ros_cloud;
115  pcl::toROSMsg(*output, ros_cloud);
116  ros_cloud.header = msg->header;
117  pub_.publish(ros_cloud);
118  }
119  }
120 
121  void VoxelGridLargeScale::configCallback(Config& config, uint32_t level)
122  {
123  boost::mutex::scoped_lock lock(mutex_);
124  leaf_size_ = config.leaf_size;
125  }
126 }
void publish(const boost::shared_ptr< M > &message) const
double max(const OneDataStat &d)
wrapper function for max method for boost::function
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void configCallback(Config &config, uint32_t level)
void output(int index, double value)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::VoxelGridLargeScale, nodelet::Nodelet)
cloud
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47