36 #define BOOST_PARAMETER_MAX_ARITY 7
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>
49 DiagnosticNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
54 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
75 pcl::PointCloud<pcl::PointXYZ>::Ptr
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
76 pcl::PointCloud<pcl::PointXYZ>::Ptr output(
new pcl::PointCloud<pcl::PointXYZ>);
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;
92 for (
int xi = 0; xi < num_x; xi++) {
93 Eigen::Vector4f min_box = min_pt + Eigen::Vector4f(box_size * xi,
97 Eigen::Vector4f max_box = min_pt + Eigen::Vector4f(box_size * (xi + 1),
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;
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;
114 sensor_msgs::PointCloud2 ros_cloud;
116 ros_cloud.header =
msg->header;