36 #define BOOST_PARAMETER_MAX_ARITY 7
38 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
39 #include <pcl/keypoints/uniform_sampling.h>
40 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
41 #include <pcl/filters/uniform_sampling.h>
49 DiagnosticNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (
f);
55 pub_ = advertise<PCLIndicesMsg>(*pnh_,
"output", 1);
77 const sensor_msgs::PointCloud2::ConstPtr&
msg)
80 pcl::PointCloud<pcl::PointXYZ>::Ptr
81 cloud (
new pcl::PointCloud<pcl::PointXYZ>);
83 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 9)
84 pcl::UniformSampling<pcl::PointXYZ> uniform_sampling(
true);
86 pcl::UniformSampling<pcl::PointXYZ> uniform_sampling;
88 uniform_sampling.setInputCloud(
cloud);
90 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
91 pcl::PointCloud<int> indices;
92 uniform_sampling.compute(indices);
93 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
94 pcl::PointCloud<pcl::PointXYZ> output;
95 uniform_sampling.filter(output);
96 pcl::PointIndicesPtr indices_ptr;
98 std::vector<int> &all_indices = *uniform_sampling.getIndices();
99 pcl::PointIndices removed_indices;
100 uniform_sampling.getRemovedIndices(removed_indices);
101 std::sort(removed_indices.indices.begin(), removed_indices.indices.end());
102 std::vector<int> indices;
103 std::set_difference(all_indices.begin(), all_indices.end(),
104 removed_indices.indices.begin(), removed_indices.indices.end(),
105 std::inserter(indices, indices.begin()));
108 #if ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION == 7)
109 for (
size_t i = 0;
i < indices.points.size();
i++) {
110 ros_indices.indices.push_back(indices.points[
i]);
112 #elif ( PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 8)
113 for (
size_t i = 0;
i < indices.size();
i++) {
114 ros_indices.indices.push_back(indices[
i]);
117 ros_indices.header =
msg->header;