multi_plane_extraction_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and 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 
38 #include <pcl/filters/extract_indices.h>
39 #include <pcl/segmentation/extract_polygonal_prism_data.h>
41 #include <jsk_topic_tools/log_utils.h>
42 #include <pcl/filters/project_inliers.h>
43 #include <set>
44 #include <sstream>
45 
46 namespace jsk_pcl_ros
47 {
48 
50  {
51  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
52  DiagnosticNodelet::onInit();
53  pnh_->param("use_indices", use_indices_, true);
54  pnh_->param("use_async", use_async_, false);
56  // Publishers
58  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
59  nonplane_pub_ = advertise<pcl::PointCloud<pcl::PointXYZRGB> >(*pnh_, "output_nonplane_cloud", 1);
60  pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/indices", 1);
61 
62  pnh_->param("max_queue_size", maximum_queue_size_, 100);
63  pnh_->param("use_coefficients", use_coefficients_, false);
64  pnh_->param("use_sensor_frame", use_sensor_frame_, false);
65  if (use_sensor_frame_) {
66  pnh_->param("sensor_frame", sensor_frame_, std::string("head_root"));
68  if (use_coefficients_) {
69  NODELET_WARN("'~use_sensor_frame' and '~use_coefficients' cannot be enabled at the same time."
70  " disabled '~use_coefficients'");
71  use_coefficients_ = false;
72  }
73  } else if (!use_coefficients_) {
74  NODELET_WARN("'~use_coefficients' and '~use_sensor_frame' are both disabled."
75  " Normal axes of planes are estimated with PCA"
76  " and they may be flipped unintentionally.");
77  }
78 
80  // Dynamic Reconfigure
82  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
83  dynamic_reconfigure::Server<Config>::CallbackType f =
84  boost::bind (&MultiPlaneExtraction::configCallback, this, _1, _2);
85  srv_->setCallback (f);
86  onInitPostProcess();
87  }
88 
90  // message_filters::Synchronizer needs to be called reset
91  // before message_filters::Subscriber is freed.
92  // Calling reset fixes the following error on shutdown of the nodelet:
93  // terminate called after throwing an instance of
94  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
95  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
96  // Also see https://github.com/ros/ros_comm/issues/720 .
97  sync_.reset();
98  async_.reset();
99  }
100 
102  {
104  // Subscribe
106 
107  sub_input_.subscribe(*pnh_, "input", 1);
108  sub_polygons_.subscribe(*pnh_, "input_polygons", 1);
109 
110  if (use_coefficients_) {
111  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
112  } else {
114  boost::bind(&MultiPlaneExtraction::fillEmptyCoefficients, this, _1));
115  }
116 
117  if (use_indices_) {
118  sub_indices_.subscribe(*pnh_, "indices", 1);
119  } else {
121  boost::bind(&MultiPlaneExtraction::fillEmptyIndices, this, _1));
122  }
123 
124  if (use_async_) {
125  async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(maximum_queue_size_);
126  if (use_indices_) {
127  if (use_coefficients_) {
129  } else {
131  }
132  } else {
135  } else {
137  }
138  }
139  async_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
140  } else {
141  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(maximum_queue_size_);
142  if (use_indices_) {
143  if (use_coefficients_) {
145  } else {
147  }
148  } else {
149  if (use_coefficients_) {
151  } else {
153  }
154  }
155  sync_->registerCallback(boost::bind(&MultiPlaneExtraction::extract, this, _1, _2, _3, _4));
156  }
157  }
158 
160  {
162  if (use_indices_) {
164  }
166  if (use_coefficients_) {
168  }
169  }
170 
171  void MultiPlaneExtraction::configCallback(Config& config, uint32_t level)
172  {
173  boost::mutex::scoped_lock lock(mutex_);
174  min_height_ = config.min_height;
175  max_height_ = config.max_height;
176  keep_organized_ = config.keep_organized;
177 
178  if (magnify_ != config.magnify)
179  {
180  magnify_ = config.magnify;
181  config.maginify = magnify_;
182  }
183  else if (magnify_ != config.maginify)
184  {
185  ROS_WARN_STREAM_ONCE("parameter 'maginify' is deprecated! Use 'magnify' instead!");
186  magnify_ = config.maginify;
187  config.magnify = magnify_;
188  }
189  }
190 
193  {
194  if (vital_checker_->isAlive()) {
195  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
196  "MultiPlaneExtraction running");
197  stat.add("Minimum Height", min_height_);
198  stat.add("Maximum Height", max_height_);
199  stat.add("Number of Planes", plane_counter_.mean());
200  }
201  DiagnosticNodelet::updateDiagnostic(stat);
202  }
203 
205  const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
206  {
207  jsk_recognition_msgs::ClusterPointIndices indices;
208  indices.header = polygons->header;
209  indices.cluster_indices.resize(polygons->polygons.size());
211  boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
212  }
213 
215  const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
216  {
217  jsk_recognition_msgs::ModelCoefficientsArray coeffs;
218  coeffs.header = polygons->header;
219  coeffs.coefficients.resize(polygons->polygons.size());
221  boost::make_shared<jsk_recognition_msgs::ModelCoefficientsArray>(coeffs));
222  }
223 
224  void MultiPlaneExtraction::extract(const sensor_msgs::PointCloud2::ConstPtr& input,
225  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
226  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
227  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
228  {
229  boost::mutex::scoped_lock lock(mutex_);
230  vital_checker_->poke();
231  // check header
232  if(!jsk_recognition_utils::isSameFrameId(input->header.frame_id,
233  indices->header.frame_id) ||
235  coefficients->header.frame_id) ||
237  polygons->header.frame_id)) {
238  std::ostringstream oss;
239  oss << "frame id does not match. cloud: " << input->header.frame_id
240  << ", polygons: " << polygons->header.frame_id;
241  if (use_indices_) {
242  oss << ", indices: " << indices->header.frame_id;
243  }
244  if (use_coefficients_) {
245  oss << ", coefficients: " << coefficients->header.frame_id;
246  }
247  NODELET_ERROR_STREAM(oss.str());
248  return;
249  }
250 
251  // set viewpoint to determine normal axes of the planes
252  Eigen::Vector3f viewpoint = Eigen::Vector3f::Zero();
253  if (use_sensor_frame_) {
254  try {
257  input->header.frame_id,
259  input->header.stamp,
260  ros::Duration(5.0));
261  Eigen::Affine3f sensor_pose;
262  tf::transformTFToEigen(transform, sensor_pose);
263  viewpoint = Eigen::Vector3f(sensor_pose.translation());
264  }
265  catch (tf2::ConnectivityException &e)
266  {
267  NODELET_ERROR("Transform error: %s", e.what());
268  }
270  {
271  NODELET_ERROR("Transform error: %s", e.what());
272  }
273  catch (...)
274  {
275  NODELET_ERROR("Unknown transform error");
276  }
277  }
278 
279  // convert all to the pcl types
280  pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
281  pcl::PointCloud<pcl::PointXYZRGB>::Ptr nonplane_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
282  pcl::fromROSMsg(*input, *input_cloud);
283  if (indices) {
284  // concat indices into one PointIndices
285  pcl::PointIndices::Ptr all_indices (new pcl::PointIndices);
286  for (size_t i = 0; i < indices->cluster_indices.size(); i++) {
287  std::vector<int> one_indices = indices->cluster_indices[i].indices;
288  for (size_t j = 0; j < one_indices.size(); j++) {
289  all_indices->indices.push_back(one_indices[j]);
290  }
291  }
292 
293 
294  pcl::ExtractIndices<pcl::PointXYZRGB> extract_nonplane;
295  extract_nonplane.setNegative(true);
296  extract_nonplane.setKeepOrganized(keep_organized_);
297  extract_nonplane.setInputCloud(input_cloud);
298  extract_nonplane.setIndices(all_indices);
299  extract_nonplane.filter(*nonplane_cloud);
300  sensor_msgs::PointCloud2 ros_result;
301  pcl::toROSMsg(*nonplane_cloud, ros_result);
302  ros_result.header = input->header;
303  nonplane_pub_.publish(ros_result);
304  }
305  else {
306  nonplane_cloud = input_cloud;
307  }
308  // for each plane, project nonplane_cloud to the plane and find the points
309  // inside of the polygon
310 
311  std::set<int> result_set;
312  plane_counter_.add(polygons->polygons.size());
313  for (size_t plane_i = 0; plane_i < polygons->polygons.size(); plane_i++) {
314  if (use_coefficients_) {
315  // set viewpoint from coefficients
316  for (size_t vec_i = 0; vec_i < 3; ++vec_i)
317  viewpoint[vec_i] = coefficients->coefficients[plane_i].values[vec_i];
318  }
319  pcl::ExtractPolygonalPrismData<pcl::PointXYZRGB> prism_extract;
320  prism_extract.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
321  pcl::PointCloud<pcl::PointXYZRGB>::Ptr hull_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());
322  geometry_msgs::Polygon the_polygon = polygons->polygons[plane_i].polygon;
323  if (the_polygon.points.size() <= 2) {
324  NODELET_WARN("too small polygon");
325  continue;
326  }
327  // compute centroid first
328  Eigen::Vector3f centroid(0, 0, 0);
329  for (size_t i = 0; i < the_polygon.points.size(); i++) {
330  pcl::PointXYZRGB p;
331  jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
332  the_polygon.points[i], p);
333  centroid = centroid + p.getVector3fMap();
334  }
335  centroid = centroid / the_polygon.points.size();
336 
337  for (size_t i = 0; i < the_polygon.points.size(); i++) {
338  pcl::PointXYZRGB p;
339  jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
340  the_polygon.points[i], p);
341  Eigen::Vector3f dir = (p.getVector3fMap() - centroid).normalized();
342  p.getVector3fMap() = dir * magnify_ + p.getVector3fMap();
343  hull_cloud->points.push_back(p);
344  }
345 
346  pcl::PointXYZRGB p_last;
347  jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
348  the_polygon.points[0], p_last);
349  hull_cloud->points.push_back(p_last);
350 
351  prism_extract.setInputCloud(nonplane_cloud);
352  prism_extract.setHeightLimits(min_height_, max_height_);
353  prism_extract.setInputPlanarHull(hull_cloud);
354  pcl::PointIndices output_indices;
355  prism_extract.segment(output_indices);
356  // append output to result_cloud
357  for (size_t i = 0; i < output_indices.indices.size(); i++) {
358  result_set.insert(output_indices.indices[i]);
359  }
360  }
361 
362  // convert std::set to PCLIndicesMsg
363  //PCLIndicesMsg output_indices;
364  pcl::PointCloud<pcl::PointXYZRGB> result_cloud;
365  pcl::PointIndices::Ptr all_result_indices (new pcl::PointIndices());
366  for (std::set<int>::iterator it = result_set.begin();
367  it != result_set.end();
368  it++) {
369  all_result_indices->indices.push_back(*it);
370  }
371 
372  pcl::ExtractIndices<pcl::PointXYZRGB> extract_all_indices;
373  extract_all_indices.setKeepOrganized(keep_organized_);
374  extract_all_indices.setInputCloud(nonplane_cloud);
375  extract_all_indices.setIndices(all_result_indices);
376  extract_all_indices.filter(result_cloud);
377 
378  sensor_msgs::PointCloud2 ros_result;
379  pcl::toROSMsg(result_cloud, ros_result);
380  ros_result.header = input->header;
381  pub_.publish(ros_result);
382  PCLIndicesMsg ros_indices;
383  pcl_conversions::fromPCL(*all_result_indices, ros_indices);
384  ros_indices.header = input->header;
385  pub_indices_.publish(ros_indices);
386  diagnostic_updater_->update();
387  }
388 }
389 
jsk_pcl_ros::MultiPlaneExtraction::magnify_
double magnify_
Definition: multi_plane_extraction.h:196
polygons
polygons
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_pcl_ros::MultiPlaneExtraction::mutex_
boost::mutex mutex_
Definition: multi_plane_extraction.h:168
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::MultiPlaneExtraction, nodelet::Nodelet)
jsk_pcl_ros::MultiPlaneExtraction::max_height_
double max_height_
Definition: multi_plane_extraction.h:194
i
int i
diagnostic_updater::DiagnosticStatusWrapper::add
void add(const std::string &key, const bool &b)
jsk_pcl_ros::MultiPlaneExtraction::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: multi_plane_extraction.h:175
jsk_pcl_ros::MultiPlaneExtraction::use_sensor_frame_
bool use_sensor_frame_
Definition: multi_plane_extraction.h:197
jsk_recognition_utils::isSameFrameId
bool isSameFrameId(const std::string &a, const std::string &b)
p
p
pcl_ros_util.h
jsk_pcl_ros::MultiPlaneExtraction::tf_listener_
tf::TransformListener * tf_listener_
Definition: multi_plane_extraction.h:190
jsk_pcl_ros::MultiPlaneExtraction::min_height_
double min_height_
Definition: multi_plane_extraction.h:194
PCLIndicesMsg
pcl::PointIndices PCLIndicesMsg
jsk_pcl_ros::MultiPlaneExtraction::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: multi_plane_extraction.h:173
NODELET_WARN
#define NODELET_WARN(...)
jsk_pcl_ros::MultiPlaneExtraction::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: multi_plane_extraction.h:178
jsk_pcl_ros::MultiPlaneExtraction::pub_
ros::Publisher pub_
Definition: multi_plane_extraction.h:169
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::MultiPlaneExtraction::async_
boost::shared_ptr< message_filters::Synchronizer< ASyncPolicy > > async_
Definition: multi_plane_extraction.h:179
ROS_WARN_STREAM_ONCE
#define ROS_WARN_STREAM_ONCE(args)
jsk_pcl_ros::MultiPlaneExtraction::subscribe
virtual void subscribe()
Definition: multi_plane_extraction_nodelet.cpp:133
jsk_pcl_ros::MultiPlaneExtraction::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: multi_plane_extraction.h:174
class_list_macros.h
jsk_pcl_ros::MultiPlaneExtraction::use_async_
bool use_async_
Definition: multi_plane_extraction.h:191
diagnostic_updater::DiagnosticStatusWrapper::summary
void summary(const diagnostic_msgs::DiagnosticStatus &src)
jsk_pcl_ros::MultiPlaneExtraction::extract
virtual void extract(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:256
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::MultiPlaneExtraction::plane_counter_
jsk_recognition_utils::Counter plane_counter_
Definition: multi_plane_extraction.h:185
jsk_recognition_utils::Counter::add
virtual void add(double v)
NODELET_ERROR_STREAM
#define NODELET_ERROR_STREAM(...)
jsk_pcl_ros::MultiPlaneExtraction::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: multi_plane_extraction.h:171
multi_plane_extraction.h
jsk_pcl_ros::MultiPlaneExtraction::pub_indices_
ros::Publisher pub_indices_
Definition: multi_plane_extraction.h:170
tf::transformTFToEigen
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3f &eigen)
jsk_pcl_ros::MultiPlaneExtraction::use_indices_
bool use_indices_
Definition: multi_plane_extraction.h:195
jsk_pcl_ros::MultiPlaneExtraction::null_coefficients_
message_filters::PassThrough< jsk_recognition_msgs::ModelCoefficientsArray > null_coefficients_
Definition: multi_plane_extraction.h:177
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const boost::function< void(P)> &callback)
message_filters::PassThrough::add
void add(const EventType &evt)
jsk_pcl_ros::MultiPlaneExtraction::keep_organized_
bool keep_organized_
Definition: multi_plane_extraction.h:192
tf2::ConnectivityException
message_filters::Subscriber::subscribe
void subscribe()
nodelet::Nodelet
jsk_pcl_ros::MultiPlaneExtraction::unsubscribe
virtual void unsubscribe()
Definition: multi_plane_extraction_nodelet.cpp:191
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::MultiPlaneExtraction::sensor_frame_
std::string sensor_frame_
Definition: multi_plane_extraction.h:198
jsk_pcl_ros::MultiPlaneExtraction::null_indices_
message_filters::PassThrough< jsk_recognition_msgs::ClusterPointIndices > null_indices_
Definition: multi_plane_extraction.h:176
jsk_pcl_ros::MultiPlaneExtraction::use_coefficients_
bool use_coefficients_
Definition: multi_plane_extraction.h:199
coefficients
coefficients
jsk_pcl_ros::MultiPlaneExtraction
Definition: multi_plane_extraction.h:92
jsk_pcl_ros::MultiPlaneExtraction::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: multi_plane_extraction_nodelet.cpp:223
jsk_recognition_utils::Counter::mean
virtual double mean()
jsk_pcl_ros::MultiPlaneExtraction::nonplane_pub_
ros::Publisher nonplane_pub_
Definition: multi_plane_extraction.h:169
diagnostic_updater::DiagnosticStatusWrapper
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::MultiPlaneExtraction::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: multi_plane_extraction_nodelet.cpp:203
lookupTransformWithDuration
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
tf2::InvalidArgumentException
jsk_pcl_ros::MultiPlaneExtraction::~MultiPlaneExtraction
virtual ~MultiPlaneExtraction()
Definition: multi_plane_extraction_nodelet.cpp:121
jsk_pcl_ros::MultiPlaneExtraction::fillEmptyCoefficients
virtual void fillEmptyCoefficients(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:246
jsk_pcl_ros::MultiPlaneExtraction::fillEmptyIndices
virtual void fillEmptyIndices(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
Definition: multi_plane_extraction_nodelet.cpp:236
config
config
ros::Duration
jsk_pcl_ros::MultiPlaneExtraction::onInit
virtual void onInit()
Definition: multi_plane_extraction_nodelet.cpp:81
jsk_pcl_ros::MultiPlaneExtraction::maximum_queue_size_
int maximum_queue_size_
Definition: multi_plane_extraction.h:193
jsk_pcl_ros::MultiPlaneExtraction::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: multi_plane_extraction.h:172


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