primitive_shape_classifier_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2017, 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  * primitive_shape_classifier_nodelet.cpp
37  * Author: Yuki Furuta <furushchev@jsk.imi.i.u-tokyo.ac.jp>
38  */
39 
41 #include <algorithm>
42 #include <iterator>
43 #include <pcl/common/centroid.h>
44 #include <pcl/features/boundary.h>
45 #include <pcl/filters/extract_indices.h>
46 #include <pcl/filters/project_inliers.h>
47 #include <pcl/sample_consensus/method_types.h>
48 #include <pcl/sample_consensus/model_types.h>
49 #include <pcl/segmentation/sac_segmentation.h>
51 
52 namespace jsk_pcl_ros
53 {
55  {
56  DiagnosticNodelet::onInit();
57 
58  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
59  dynamic_reconfigure::Server<Config>::CallbackType f =
60  boost::bind(&PrimitiveShapeClassifier::configCallback, this, _1, _2);
61  srv_->setCallback(f);
62 
63  pub_class_ = advertise<jsk_recognition_msgs::ClassificationResult>(*pnh_, "output", 1);
65  advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "debug/boundary_indices", 1);
67  advertise<sensor_msgs::PointCloud2>(*pnh_, "debug/projected_cloud", 1);
68 
69  onInitPostProcess();
70  }
71 
73  // message_filters::Synchronizer needs to be called reset
74  // before message_filters::Subscriber is freed.
75  // Calling reset fixes the following error on shutdown of the nodelet:
76  // terminate called after throwing an instance of
77  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
78  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
79  // Also see https://github.com/ros/ros_comm/issues/720 .
80  sync_.reset();
81  }
82 
84  {
85  sub_cloud_.subscribe(*pnh_, "input", 1);
86  sub_normal_.subscribe(*pnh_, "input/normal", 1);
87  sub_indices_.subscribe(*pnh_, "input/indices", 1);
88  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
89 
90  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
92  sync_->registerCallback(boost::bind(&PrimitiveShapeClassifier::process, this, _1, _2, _3, _4));
93  }
94 
96  {
101  }
102 
103  void PrimitiveShapeClassifier::configCallback(Config& config, uint32_t level)
104  {
105  boost::mutex::scoped_lock lock(mutex_);
106  min_points_num_ = config.min_points_num;
107 
108  sac_max_iterations_ = config.sac_max_iterations;
109  sac_distance_threshold_ = config.sac_distance_threshold;
110  if (config.sac_radius_limit_min < config.sac_radius_limit_max) {
111  sac_radius_limit_min_ = config.sac_radius_limit_min;
112  sac_radius_limit_max_ = config.sac_radius_limit_max;
113  } else {
114  config.sac_radius_limit_min = sac_radius_limit_min_;
115  config.sac_radius_limit_max = sac_radius_limit_max_;
116  }
117 
118  box_threshold_ = config.box_threshold;
119  circle_threshold_ = config.circle_threshold;
120 
121  if (queue_size_ != config.queue_size) {
122  queue_size_ = config.queue_size;
123  if (isSubscribed()) {
124  unsubscribe();
125  subscribe();
126  }
127  }
128  }
129 
130  bool
131  PrimitiveShapeClassifier::checkFrameId(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
132  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
133  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
134  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons)
135  {
136  std::string cloud_topic = ros::names::resolve(sub_cloud_.getTopic());
137  std::string normal_topic = ros::names::resolve(sub_normal_.getTopic());
138  std::string indices_topic = ros::names::resolve(sub_indices_.getTopic());
139  std::string polygons_topic = ros::names::resolve(sub_polygons_.getTopic());
140  if (!jsk_recognition_utils::isSameFrameId(ros_cloud->header, ros_normal->header)) {
141  NODELET_ERROR_STREAM(cloud_topic << " and " << normal_topic << " must have same frame_id");
142  return false;
143  }
144  if (!jsk_recognition_utils::isSameFrameId(ros_cloud->header, ros_indices->header)) {
145  NODELET_ERROR_STREAM(cloud_topic << " and " << indices_topic << " must have same frame_id");
146  return false;
147  }
148  if (!jsk_recognition_utils::isSameFrameId(ros_cloud->header, ros_polygons->header)) {
149  NODELET_ERROR_STREAM(cloud_topic << " and " << polygons_topic << " must have same frame_id");
150  return false;
151  }
152  NODELET_DEBUG_STREAM("Frame id is ok: " << ros_cloud->header.frame_id);
153  return true;
154  }
155 
156  void
157  PrimitiveShapeClassifier::process(const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
158  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
159  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
160  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons)
161  {
162  boost::mutex::scoped_lock lock(mutex_);
163 
164  if (!checkFrameId(ros_cloud, ros_normal, ros_indices, ros_polygons)) return;
165 
166  pcl::PointCloud<PointT>::Ptr input(new pcl::PointCloud<PointT>);
167  pcl::fromROSMsg(*ros_cloud, *input);
168 
169  pcl::PointCloud<pcl::Normal>::Ptr normal(new pcl::PointCloud<pcl::Normal>);
170  pcl::fromROSMsg(*ros_normal, *normal);
171 
172  pcl::ExtractIndices<PointT> ext_input;
173  ext_input.setInputCloud(input);
174  pcl::ExtractIndices<pcl::Normal> ext_normal;
175  ext_normal.setInputCloud(normal);
176 
177  std::vector<jsk_recognition_utils::Polygon::Ptr> polygons
179 
180  jsk_recognition_msgs::ClassificationResult result;
181  result.header = ros_cloud->header;
182  result.classifier = "primitive_shape_classifier";
183  result.target_names.push_back("box");
184  result.target_names.push_back("circle");
185  result.target_names.push_back("other");
186 
187  pcl::PointCloud<PointT>::Ptr projected_cloud(new pcl::PointCloud<PointT>);
188  std::vector<pcl::PointIndices::Ptr> boundary_indices;
189 
190  NODELET_DEBUG_STREAM("Cluster num: " << ros_indices->cluster_indices.size());
191  for (size_t i = 0; i < ros_indices->cluster_indices.size(); ++i)
192  {
193  pcl::PointIndices::Ptr indices(new pcl::PointIndices);
194  indices->indices = ros_indices->cluster_indices[i].indices;
195  NODELET_DEBUG_STREAM("Estimating cluster #" << i << " (" << indices->indices.size() << " points)");
196 
197  pcl::PointCloud<PointT>::Ptr cluster_cloud(new pcl::PointCloud<PointT>);
198  ext_input.setIndices(indices);
199  ext_input.filter(*cluster_cloud);
200 
201  pcl::PointCloud<pcl::Normal>::Ptr cluster_normal(new pcl::PointCloud<pcl::Normal>);
202  ext_normal.setIndices(indices);
203  ext_normal.filter(*cluster_normal);
204 
205  pcl::ModelCoefficients::Ptr support_plane(new pcl::ModelCoefficients);
206  if (!getSupportPlane(cluster_cloud, polygons, support_plane))
207  {
208  NODELET_ERROR_STREAM("cloud " << i << " has no support plane. skipped");
209  continue;
210  }
211 
212  pcl::PointIndices::Ptr b(new pcl::PointIndices);
213  pcl::PointCloud<PointT>::Ptr pc(new pcl::PointCloud<PointT>);
214  float circle_likelihood, box_likelihood;
215  estimate(cluster_cloud, cluster_normal, support_plane,
216  b, pc,
217  circle_likelihood, box_likelihood);
218  boundary_indices.push_back(std::move(b));
219  *projected_cloud += *pc;
220 
221  if (circle_likelihood > circle_threshold_) {
222  // circle
223  result.labels.push_back(1);
224  result.label_names.push_back("circle");
225  result.label_proba.push_back(circle_likelihood);
226  } else if (box_likelihood > box_threshold_) {
227  // box
228  result.labels.push_back(0);
229  result.label_names.push_back("box");
230  result.label_proba.push_back(box_likelihood);
231  } else {
232  // other
233  result.labels.push_back(3);
234  result.label_names.push_back("other");
235  result.label_proba.push_back(0.0);
236  }
237  }
238 
239  // publish results
241  sensor_msgs::PointCloud2 ros_projected_cloud;
242  pcl::toROSMsg(*projected_cloud, ros_projected_cloud);
243  ros_projected_cloud.header = ros_cloud->header;
244  pub_projected_cloud_.publish(ros_projected_cloud);
245  }
246 
248  jsk_recognition_msgs::ClusterPointIndices ros_boundary_indices;
249  ros_boundary_indices.header = ros_cloud->header;
250  for (size_t i = 0; i < boundary_indices.size(); ++i)
251  {
252  pcl_msgs::PointIndices ri;
253  pcl_conversions::moveFromPCL(*boundary_indices[i], ri);
254  ros_boundary_indices.cluster_indices.push_back(ri);
255  }
256  pub_boundary_indices_.publish(ros_boundary_indices);
257  }
258 
259  pub_class_.publish(result);
260  }
261 
262  bool
263  PrimitiveShapeClassifier::estimate(const pcl::PointCloud<PointT>::Ptr& cloud,
264  const pcl::PointCloud<pcl::Normal>::Ptr& normal,
265  const pcl::ModelCoefficients::Ptr& plane,
266  pcl::PointIndices::Ptr& boundary_indices,
267  pcl::PointCloud<PointT>::Ptr& projected_cloud,
268  float& circle_likelihood,
269  float& box_likelihood)
270  {
271  // estimate boundaries
272  pcl::PointCloud<pcl::Boundary>::Ptr boundaries(new pcl::PointCloud<pcl::Boundary>);
273  pcl::BoundaryEstimation<PointT, pcl::Normal, pcl::Boundary> b;
274  b.setInputCloud(cloud);
275  b.setInputNormals(normal);
276  b.setSearchMethod(typename pcl::search::KdTree<PointT>::Ptr(new pcl::search::KdTree<PointT>));
277  b.setAngleThreshold(DEG2RAD(70));
278  b.setRadiusSearch(0.03);
279  b.compute(*boundaries);
280 
281  // set boundaries as indices
282  for (size_t i = 0; i < boundaries->points.size(); ++i)
283  if ((int)boundaries->points[i].boundary_point)
284  boundary_indices->indices.push_back(i);
285 
286  // extract boundaries
287  pcl::PointCloud<PointT>::Ptr boundary_cloud(new pcl::PointCloud<PointT>);
288  pcl::ExtractIndices<PointT> ext;
289  ext.setInputCloud(cloud);
290  ext.setIndices(boundary_indices);
291  ext.filter(*boundary_cloud);
292 
293  // thresholding with min points num
294  if (boundary_indices->indices.size() < min_points_num_)
295  return false;
296 
297  // project to supporting plane
298  pcl::ProjectInliers<PointT> proj;
299  proj.setModelType(pcl::SACMODEL_PLANE);
300  proj.setInputCloud(boundary_cloud);
301  proj.setModelCoefficients(plane);
302  proj.filter(*projected_cloud);
303 
304  // estimate circles
305  pcl::PointIndices::Ptr circle_inliers(new pcl::PointIndices);
306  pcl::ModelCoefficients::Ptr circle_coeffs(new pcl::ModelCoefficients);
307  pcl::PointIndices::Ptr line_inliers(new pcl::PointIndices);
308  pcl::ModelCoefficients::Ptr line_coeffs(new pcl::ModelCoefficients);
309 
310  pcl::SACSegmentation<PointT> seg;
311  seg.setInputCloud(projected_cloud);
312 
313  seg.setOptimizeCoefficients(true);
314  seg.setMethodType(pcl::SAC_RANSAC);
315  seg.setMaxIterations(sac_max_iterations_);
316  seg.setModelType(pcl::SACMODEL_CIRCLE3D);
317  seg.setDistanceThreshold(sac_distance_threshold_);
318  seg.setRadiusLimits(sac_radius_limit_min_, sac_radius_limit_max_);
319  seg.segment(*circle_inliers, *circle_coeffs);
320 
321  seg.setOptimizeCoefficients(true);
322  seg.setMethodType(pcl::SAC_RANSAC);
323  seg.setMaxIterations(sac_max_iterations_);
324  seg.setModelType(pcl::SACMODEL_LINE);
325  seg.setDistanceThreshold(sac_distance_threshold_);
326  seg.segment(*line_inliers, *line_coeffs);
327 
328  // compute likelihood
329  circle_likelihood =
330  1.0f * circle_inliers->indices.size() / projected_cloud->points.size();
331  box_likelihood =
332  1.0f * line_inliers->indices.size() / projected_cloud->points.size();
333 
334  NODELET_DEBUG_STREAM("Projected cloud has " << projected_cloud->points.size() << " points");
335  NODELET_DEBUG_STREAM(circle_inliers->indices.size() << " circle inliers found");
336  NODELET_DEBUG_STREAM("circle confidence: " << circle_likelihood);
337  NODELET_DEBUG_STREAM(line_inliers->indices.size() << " line inliers found");
338  NODELET_DEBUG_STREAM("box confidence: " << box_likelihood);
339 
340  return true;
341  }
342 
343  bool
344  PrimitiveShapeClassifier::getSupportPlane(const pcl::PointCloud<PointT>::Ptr& cloud,
345  const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
346  pcl::ModelCoefficients::Ptr& coeff)
347  {
348  Eigen::Vector4f c;
349  pcl::compute3DCentroid(*cloud, c);
350  Eigen::Vector3f centroid(c[0], c[1], c[2]);
351  Eigen::Vector3f projected;
352  for (size_t i = 0; i < polygons.size(); ++i)
353  {
355  p->project(centroid, projected);
356  if (p->isInside(projected)) {
357  p->toCoefficients(coeff->values);
358  return true;
359  }
360  }
361  return false;
362  }
363 }
364 
result
def result
polygons
polygons
jsk_pcl_ros::PrimitiveShapeClassifier::checkFrameId
virtual bool checkFrameId(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
Definition: primitive_shape_classifier_nodelet.cpp:163
jsk_pcl_ros::PrimitiveShapeClassifier::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: primitive_shape_classifier.h:176
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::PrimitiveShapeClassifier::estimate
virtual bool estimate(const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const pcl::ModelCoefficients::Ptr &plane, pcl::PointIndices::Ptr &boundary_indices, pcl::PointCloud< PointT >::Ptr &projected_cloud, float &circle_likelihood, float &box_likelihood)
Definition: primitive_shape_classifier_nodelet.cpp:295
boost::shared_ptr
i
int i
jsk_pcl_ros::PrimitiveShapeClassifier::pub_boundary_indices_
ros::Publisher pub_boundary_indices_
Definition: primitive_shape_classifier.h:179
jsk_recognition_utils::isSameFrameId
bool isSameFrameId(const std::string &a, const std::string &b)
p
p
jsk_pcl_ros::PrimitiveShapeClassifier
Definition: primitive_shape_classifier.h:94
jsk_pcl_ros::PrimitiveShapeClassifier::unsubscribe
virtual void unsubscribe()
Definition: primitive_shape_classifier_nodelet.cpp:127
simulate_primitive_shape_on_plane.c
c
Definition: simulate_primitive_shape_on_plane.py:103
jsk_pcl_ros::PrimitiveShapeClassifier::circle_threshold_
double circle_threshold_
Definition: primitive_shape_classifier.h:188
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::PrimitiveShapeClassifier::sub_normal_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
Definition: primitive_shape_classifier.h:174
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::PrimitiveShapeClassifier::mutex_
boost::mutex mutex_
Definition: primitive_shape_classifier.h:171
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
jsk_pcl_ros::PrimitiveShapeClassifier::queue_size_
int queue_size_
Definition: primitive_shape_classifier.h:183
message_filters::Subscriber::getTopic
std::string getTopic() const
jsk_pcl_ros::PrimitiveShapeClassifier::pub_class_
ros::Publisher pub_class_
Definition: primitive_shape_classifier.h:178
jsk_pcl_ros::PrimitiveShapeClassifier::subscribe
virtual void subscribe()
Definition: primitive_shape_classifier_nodelet.cpp:115
jsk_pcl_ros::PrimitiveShapeClassifier::~PrimitiveShapeClassifier
virtual ~PrimitiveShapeClassifier()
Definition: primitive_shape_classifier_nodelet.cpp:104
jsk_pcl_ros::PrimitiveShapeClassifier::min_points_num_
int min_points_num_
Definition: primitive_shape_classifier.h:184
class_list_macros.h
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_recognition_utils::Polygon::fromROSMsg
static Polygon fromROSMsg(const geometry_msgs::Polygon &polygon)
jsk_pcl_ros::PrimitiveShapeClassifier::process
virtual void process(const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons)
Definition: primitive_shape_classifier_nodelet.cpp:189
jsk_pcl_ros::PrimitiveShapeClassifier::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: primitive_shape_classifier.h:172
NODELET_ERROR_STREAM
#define NODELET_ERROR_STREAM(...)
jsk_pcl_ros::PrimitiveShapeClassifier::box_threshold_
double box_threshold_
Definition: primitive_shape_classifier.h:188
DEG2RAD
#define DEG2RAD
jsk_pcl_ros::PrimitiveShapeClassifier::sac_max_iterations_
int sac_max_iterations_
Definition: primitive_shape_classifier.h:185
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::PrimitiveShapeClassifier::getSupportPlane
virtual bool getSupportPlane(const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< jsk_recognition_utils::Polygon::Ptr > &polygons, pcl::ModelCoefficients::Ptr &coeff)
Definition: primitive_shape_classifier_nodelet.cpp:376
nodelet::Nodelet
jsk_pcl_ros::PrimitiveShapeClassifier::sac_distance_threshold_
double sac_distance_threshold_
Definition: primitive_shape_classifier.h:186
jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_min_
double sac_radius_limit_min_
Definition: primitive_shape_classifier.h:187
jsk_pcl_ros::PrimitiveShapeClassifier::onInit
virtual void onInit()
Definition: primitive_shape_classifier_nodelet.cpp:86
dump_depth_error.f
f
Definition: dump_depth_error.py:39
NODELET_DEBUG_STREAM
#define NODELET_DEBUG_STREAM(...)
jsk_pcl_ros::PrimitiveShapeClassifier::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: primitive_shape_classifier.h:177
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_max_
double sac_radius_limit_max_
Definition: primitive_shape_classifier.h:187
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PrimitiveShapeClassifier, nodelet::Nodelet)
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
jsk_pcl_ros::PrimitiveShapeClassifier::sub_cloud_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
Definition: primitive_shape_classifier.h:173
jsk_pcl_ros::PrimitiveShapeClassifier::pub_projected_cloud_
ros::Publisher pub_projected_cloud_
Definition: primitive_shape_classifier.h:180
primitive_shape_classifier.h
config
config
jsk_pcl_ros::PrimitiveShapeClassifier::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: primitive_shape_classifier.h:175
jsk_pcl_ros::PrimitiveShapeClassifier::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: primitive_shape_classifier_nodelet.cpp:135
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:45