36 #define BOOST_PARAMETER_MAX_ARITY 7
40 #if PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 8
41 #include <pcl/filters/extract_indices.h>
46 #include <sensor_msgs/PointCloud2.h>
52 DiagnosticNodelet::onInit();
54 pnh_->param(
"negative",
negative_,
false);
57 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
78 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
84 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
86 sync_->registerCallback(
98 const PCLIndicesMsg::ConstPtr& indices_msg,
99 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
101 vital_checker_->poke();
103 pcl::PCLPointCloud2::Ptr
input(
new pcl::PCLPointCloud2);
105 pcl::PointIndices::Ptr indices (
new pcl::PointIndices ());
109 int32_t data_size =
static_cast<int32_t
>(
input->data.size());
110 int32_t point_step_size =
static_cast<int32_t
>(
input->point_step);
111 int32_t cloud_size = data_size / point_step_size;
112 int32_t indices_size =
static_cast<int32_t
>(indices->indices.size());
113 if (cloud_size < indices_size){
114 NODELET_ERROR(
"Input index is out of expected cloud size: %d > %d", indices_size, cloud_size);
119 pcl::ExtractIndices<pcl::PCLPointCloud2> extract;
120 extract.setInputCloud(
input);
121 extract.setIndices(indices);
124 pcl::PCLPointCloud2 output;
125 extract.filter(output);
127 sensor_msgs::PointCloud2 out_cloud_msg;
128 #if PCL_MAJOR_VERSION <= 1 && PCL_MINOR_VERSION < 8
129 if (indices_msg->indices.empty() || cloud_msg->data.empty()) {
130 out_cloud_msg.height = cloud_msg->height;
131 out_cloud_msg.width = cloud_msg->width;
136 out_cloud_msg.header = cloud_msg->header;