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();
57 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
66 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
72 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
74 sync_->registerCallback(
86 const PCLIndicesMsg::ConstPtr& indices_msg,
87 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
91 pcl::PCLPointCloud2::Ptr input(
new pcl::PCLPointCloud2);
93 pcl::PointIndices::Ptr indices (
new pcl::PointIndices ());
97 pcl::ExtractIndices<pcl::PCLPointCloud2> extract;
98 extract.setInputCloud(input);
99 extract.setIndices(indices);
102 pcl::PCLPointCloud2
output;
103 extract.filter(output);
105 sensor_msgs::PointCloud2 out_cloud_msg;
106 #if PCL_MAJOR_VERSION <= 1 && PCL_MINOR_VERSION < 8 107 if (indices_msg->indices.empty() || cloud_msg->data.empty()) {
108 out_cloud_msg.height = cloud_msg->height;
109 out_cloud_msg.width = cloud_msg->width;
114 out_cloud_msg.header = cloud_msg->header;
void publish(const boost::shared_ptr< M > &message) const
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
void output(int index, double value)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)