extract_indices_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/or 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
39 
40 #if PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 8
41 #include <pcl/filters/extract_indices.h>
42 #else
44 #endif
46 #include <sensor_msgs/PointCloud2.h>
47 
48 namespace jsk_pcl_ros
49 {
51  {
52  DiagnosticNodelet::onInit();
53  pnh_->param("keep_organized", keep_organized_, false);
54  pnh_->param("negative", negative_, false);
55  pnh_->param("max_queue_size", max_queue_size_, 10);
56  pnh_->param("approximate_sync", approximate_sync_, false);
57  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
58  onInitPostProcess();
59  }
60 
62  // message_filters::Synchronizer needs to be called reset
63  // before message_filters::Subscriber is freed.
64  // Calling reset fixes the following error on shutdown of the nodelet:
65  // terminate called after throwing an instance of
66  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
67  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
68  // Also see https://github.com/ros/ros_comm/issues/720 .
69  sync_.reset();
70  async_.reset();
71  }
72 
74  {
75  sub_cloud_.subscribe(*pnh_, "input", max_queue_size_);
76  sub_indices_.subscribe(*pnh_, "indices", max_queue_size_);
77  if (approximate_sync_) {
78  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
79  async_->connectInput(sub_indices_, sub_cloud_);
80  async_->registerCallback(
81  boost::bind(&ExtractIndices::convert, this, _1, _2));
82  }
83  else {
84  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
85  sync_->connectInput(sub_indices_, sub_cloud_);
86  sync_->registerCallback(
87  boost::bind(&ExtractIndices::convert, this, _1, _2));
88  }
89  }
90 
92  {
95  }
96 
98  const PCLIndicesMsg::ConstPtr& indices_msg,
99  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
100  {
101  vital_checker_->poke();
102 
103  pcl::PCLPointCloud2::Ptr input(new pcl::PCLPointCloud2);
104  pcl_conversions::toPCL(*cloud_msg, *input);
105  pcl::PointIndices::Ptr indices (new pcl::PointIndices ());
106  pcl_conversions::toPCL(*indices_msg, *indices);
107 
108  // check if input size is bigger than indices size
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);
115  return;
116  }
117 
118  // extract pointcloud with indices
119  pcl::ExtractIndices<pcl::PCLPointCloud2> extract;
120  extract.setInputCloud(input);
121  extract.setIndices(indices);
122  extract.setKeepOrganized(keep_organized_);
123  extract.setNegative(negative_);
124  pcl::PCLPointCloud2 output;
125  extract.filter(output);
126 
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;
132  }
133 #endif
134  pcl_conversions::moveFromPCL(output, out_cloud_msg);
135 
136  out_cloud_msg.header = cloud_msg->header;
137  pub_.publish(out_cloud_msg);
138  }
139 }
140 
jsk_pcl_ros::ExtractIndices::unsubscribe
virtual void unsubscribe()
Definition: extract_indices_nodelet.cpp:91
NODELET_ERROR
#define NODELET_ERROR(...)
_2
boost::arg< 2 > _2
jsk_pcl_ros::ExtractIndices
Definition: extract_indices.h:82
jsk_pcl_ros::ExtractIndices::pub_
ros::Publisher pub_
Definition: extract_indices.h:140
jsk_pcl_ros::ExtractIndices::onInit
virtual void onInit()
Definition: extract_indices_nodelet.cpp:50
jsk_pcl_ros::ExtractIndices::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: extract_indices.h:138
jsk_pcl_ros::ExtractIndices::sub_indices_
message_filters::Subscriber< PCLIndicesMsg > sub_indices_
Definition: extract_indices.h:142
jsk_pcl_ros::ExtractIndices::negative_
bool negative_
Definition: extract_indices.h:135
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
extract_indices_patch.h
jsk_pcl_ros::ExtractIndices::convert
virtual void convert(const PCLIndicesMsg::ConstPtr &indices_msg, const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: extract_indices_nodelet.cpp:97
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::ExtractIndices::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: extract_indices.h:141
class_list_macros.h
jsk_pcl_ros::ExtractIndices::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: extract_indices.h:139
jsk_pcl_ros
Definition: add_color_from_image.h:51
extract_indices.h
_1
boost::arg< 1 > _1
jsk_pcl_ros::ExtractIndices::approximate_sync_
bool approximate_sync_
Definition: extract_indices.h:137
pcl_conversion_util.h
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::ExtractIndices::subscribe
virtual void subscribe()
Definition: extract_indices_nodelet.cpp:73
nodelet::Nodelet
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ExtractIndices, nodelet::Nodelet)
jsk_pcl_ros::ExtractIndices::max_queue_size_
int max_queue_size_
Definition: extract_indices.h:136
jsk_pcl_ros::ExtractIndices::keep_organized_
bool keep_organized_
Definition: extract_indices.h:134
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::ExtractIndices::~ExtractIndices
virtual ~ExtractIndices()
Definition: extract_indices_nodelet.cpp:61
pcl_conversions::moveFromPCL
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
pcl_conversions.h


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44