line_segment_collector_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 #define BOOST_PARAMETER_MAX_ARITY 7
39 #include <pcl/sample_consensus/method_types.h>
40 #include <pcl/sample_consensus/model_types.h>
41 #include <pcl/segmentation/sac_segmentation.h>
42 
43 namespace jsk_pcl_ros
44 {
46  delta_(Eigen::Vector3f(0, 0, 0)),
47  points_(new pcl::PointCloud<pcl::PointXYZ>),
48  raw_points_(new pcl::PointCloud<pcl::PointXYZ>)
49  {
50 
51  }
52 
54  LineSegment::Ptr segment, const double tau)
55  {
56  segments_.push_back(segment);
57  Eigen::Vector3f new_delta = segment->toSegment()->getDirection();
58  if (new_delta.dot(delta_) < 0) {
59  new_delta = - new_delta;
60  }
61  delta_ = ((1 - tau) * delta_ + tau * new_delta).normalized();
62 
63  // update points_
64  pcl::PointCloud<pcl::PointXYZ>::Ptr new_cloud = segment->getPoints();
65  for (size_t i = 0; i < new_cloud->points.size(); i++) {
66  points_->points.push_back(new_cloud->points[i]);
67  }
68  // update raw_points_
69  pcl::PointCloud<pcl::PointXYZ>::Ptr new_raw_cloud = segment->getRawPoints();
70  for (size_t i = 0; i < new_raw_cloud->points.size(); i++) {
71  raw_points_->points.push_back(new_raw_cloud->points[i]);
72  }
73  }
74 
75  pcl::PointCloud<pcl::PointXYZ>::Ptr LineSegmentCluster::getPoints()
76  {
77  return points_;
78  }
79 
80  pcl::PointCloud<pcl::PointXYZ>::Ptr LineSegmentCluster::getRawPoints()
81  {
82  return raw_points_;
83  }
84 
86  {
87  bool removed = false;
88  for (std::vector<LineSegment::Ptr>::iterator it = segments_.begin();
89  it != segments_.end(); ) {
90  if (((*it)->header.stamp - stamp).toSec() < 0) {
91  it = segments_.erase(it);
92  removed = true;
93  }
94  else {
95  ++it;
96  }
97  }
98  if (removed) {
99  // reconstruct pointcloud
100  points_.reset(new pcl::PointCloud<pcl::PointXYZ>);
101 
102  raw_points_.reset(new pcl::PointCloud<pcl::PointXYZ>);
103  for (std::vector<LineSegment::Ptr>::iterator it = segments_.begin();
104  it != segments_.end(); ++it) {
105  {
106  pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getPoints();
107  for (size_t i = 0; i < segment_points->points.size(); i++) {
108  points_->points.push_back(segment_points->points[i]);
109  }
110  }
111  {
112  pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getRawPoints();
113  for (size_t i = 0; i < segment_points->points.size(); i++) {
114  raw_points_->points.push_back(segment_points->points[i]);
115  }
116  }
117  }
118  }
119  }
120 
122  {
123  return segments_.size() == 0;
124  }
125 
127  {
128  DiagnosticNodelet::onInit();
129  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
130  dynamic_reconfigure::Server<Config>::CallbackType f =
131  boost::bind (&LineSegmentCollector::configCallback, this, _1, _2);
132  srv_->setCallback (f);
133 
134  std::string rotate_type_str;
135  pnh_->param("rotate_type", rotate_type_str, std::string("tilt_two_way"));
136  if (rotate_type_str == "tilt") {
138  }
139  else if (rotate_type_str == "tilt_two_way") {
141  }
142  else if (rotate_type_str == "spindle") {
144  }
145  else {
146  NODELET_ERROR("unknown ~rotate_type: %s", rotate_type_str.c_str());
147  return;
148  }
149 
151  = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
152  pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/inliers", 1);
154  = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/coefficients", 1);
156  = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/polygons", 1);
158  = advertise<jsk_recognition_msgs::ClusterPointIndices>(
159  *pnh_, "debug/connect_segments/inliers", 1);
160 
161  onInitPostProcess();
162  }
163 
165  // message_filters::Synchronizer needs to be called reset
166  // before message_filters::Subscriber is freed.
167  // Calling reset fixes the following error on shutdown of the nodelet:
168  // terminate called after throwing an instance of
169  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
170  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
171  // Also see https://github.com/ros/ros_comm/issues/720 .
172  sync_.reset();
173  }
174 
175  void LineSegmentCollector::configCallback(Config &config, uint32_t level)
176  {
177  boost::mutex::scoped_lock lock(mutex_);
178  ewma_tau_ = config.ewma_tau;
179  segment_connect_normal_threshold_ = config.segment_connect_normal_threshold;
180  outlier_threshold_ = config.outlier_threshold;
181  }
182 
184  {
185  sub_input_.subscribe(*pnh_, "input", 1);
186  sub_indices_.subscribe(*pnh_, "input_indices", 1);
187  sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
188  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
190  sync_->registerCallback(boost::bind(&LineSegmentCollector::collect,
191  this, _1, _2, _3));
192  sub_trigger_ = pnh_->subscribe("trigger", 1,
194  }
195 
197  {
202  }
203 
205  const ros::Time& stamp)
206  {
210  segments_buffer_.removeBefore(stamp);
211  for (std::vector<LineSegmentCluster::Ptr>::iterator it = segment_clusters_.begin();
212  it != segment_clusters_.end();) {
213  (*it)->removeBefore(stamp);
214  if ((*it)->isEmpty()) {
215  it = segment_clusters_.erase(it);
216  }
217  else {
218  ++it;
219  }
220  }
221  }
222 
224  const jsk_recognition_msgs::TimeRange::ConstPtr& trigger)
225  {
226  boost::mutex::scoped_lock lock(mutex_);
227  time_range_ = trigger;
228  cleanupBuffers(time_range_->start);
229  }
230 
232  const std_msgs::Header& header,
233  const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
234  const std::vector<pcl::PointIndices::Ptr>& connected_indices)
235  {
236  sensor_msgs::PointCloud2 ros_cloud;
237  pcl::toROSMsg(*cloud, ros_cloud);
238  ros_cloud.header = header;
239  pub_point_cloud_.publish(ros_cloud);
240  jsk_recognition_msgs::ClusterPointIndices ros_indices;
241  ros_indices.header = header;
242  ros_indices.cluster_indices
245  }
246 
248  LineSegment::Ptr segment)
249  {
250  int max_index = -1;
251  double max_dot = - DBL_MAX;
252  for (size_t i = 0; i < segment_clusters_.size(); i++) {
254  Eigen::Vector3f delta_cluster = cluster->getDelta();
255  Eigen::Vector3f delta = segment->toSegment()->getDirection();
256  double delta_dot = std::abs(delta_cluster.dot(delta));
257  if (delta_dot > segment_connect_normal_threshold_) {
258  if (max_dot < delta_dot) {
259  max_dot = delta_dot;
260  max_index = i;
261  }
262  }
263  // else {
264  // if (segment_clusters_.size() != 0) {
265  // NODELET_INFO("dot: %f", delta_dot);
266  // }
267  // }
268  }
269  if (max_index == -1) {
270 
271  return LineSegmentCluster::Ptr();
272  }
273  else {
274  //ROS_INFO("max angle: %f", acos(max_dot) * 180.0 / M_PI);
275  return segment_clusters_[max_index];
276  }
277  }
278 
280  const std_msgs::Header& header,
281  std::vector<LineSegment::Ptr> new_segments)
282  {
283  for (size_t i = 0; i < new_segments.size(); i++) {
284  LineSegment::Ptr segment = new_segments[i];
286  if (cluster) {
287  cluster->addLineSegmentEWMA(segment, ewma_tau_);
288  }
289  else {
290  cluster.reset(new LineSegmentCluster());
291  cluster->addLineSegmentEWMA(segment, 1.0);
292  segment_clusters_.push_back(cluster);
293  }
294  }
295 
296  pcl::PointCloud<pcl::PointXYZ>::Ptr
297  connected_cloud(new pcl::PointCloud<pcl::PointXYZ>);
298  std::vector<pcl::PointIndices::Ptr> connected_indices;
299  std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > clouds_list;
300  for (size_t i = 0; i < segment_clusters_.size(); i++) {
302  pcl::PointIndices::Ptr current_indices (new pcl::PointIndices);
303  pcl::PointCloud<pcl::PointXYZ>::Ptr current_cloud
304  = cluster->getRawPoints();
305  for (size_t j = 0; j < current_cloud->points.size(); j++) {
306  current_indices->indices.push_back(connected_cloud->points.size() + j);
307  }
308  connected_indices.push_back(current_indices);
309  clouds_list.push_back(current_cloud);
310  *connected_cloud = *connected_cloud + *current_cloud;
311  }
312  // publish debug information
314  header,
315  connected_cloud,
316  connected_indices);
317  }
318 
320  const std_msgs::Header& header,
321  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
322  std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
323  std::vector<pcl::PointIndices::Ptr> all_indices)
324  {
325  jsk_recognition_msgs::ClusterPointIndices ros_indices;
326  ros_indices.header = header;
327  ros_indices.cluster_indices
329  header);
330  pub_inliers_.publish(ros_indices);
331  jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
332  ros_coefficients.header = header;
333  ros_coefficients.coefficients
335  all_coefficients,
336  header);
337  pub_coefficients_.publish(ros_coefficients);
338  jsk_recognition_msgs::PolygonArray ros_polygon;
339  ros_polygon.header = header;
340  for (size_t i = 0; i < all_indices.size(); i++) {
342  = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointXYZ>(
343  cloud, all_indices[i], all_coefficients[i]);
344  geometry_msgs::PolygonStamped polygon_stamped;
345  polygon_stamped.header = header;
346  polygon_stamped.polygon = convex->toROSMsg();
347  ros_polygon.polygons.push_back(polygon_stamped);
348  }
349  pub_polygons_.publish(ros_polygon);
350  }
351 
353  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
354  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
355  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
356  {
357  boost::mutex::scoped_lock lock(mutex_);
358  //NODELET_INFO("buffer length: %lu", pointclouds_buffer_.size());
359  pointclouds_buffer_.push_back(cloud_msg);
360  indices_buffer_.push_back(indices_msg);
361  coefficients_buffer_.push_back(coefficients_msg);
362  pcl::PointCloud<pcl::PointXYZ>::Ptr
363  input_cloud(new pcl::PointCloud<pcl::PointXYZ>);
364  pcl::fromROSMsg(*cloud_msg, *input_cloud);
365  // buildup segments
366  std::vector<pcl::PointIndices::Ptr> input_indices
367  = pcl_conversions::convertToPCLPointIndices(indices_msg->cluster_indices);
368  std::vector<pcl::ModelCoefficients::Ptr> input_coefficients
370  coefficients_msg->coefficients);
371  std::vector<LineSegment::Ptr> new_segments;
372  for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
373  LineSegment::Ptr segment (new LineSegment(cloud_msg->header,
374  input_indices[i],
375  input_coefficients[i],
376  input_cloud));
377  segments_buffer_.push_back(segment);
378  new_segments.push_back(segment);
379  }
380  collectFromBuffers(cloud_msg->header, new_segments);
381  }
382 
383 }
384 
pcl
jsk_pcl_ros::LineSegmentCollector::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: line_segment_collector_nodelet.cpp:175
jsk_pcl_ros::LineSegmentCollector::sub_trigger_
ros::Subscriber sub_trigger_
Definition: line_segment_collector.h:195
NODELET_ERROR
#define NODELET_ERROR(...)
Eigen
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
jsk_pcl_ros::TimeStampedVector::removeBefore
void removeBefore(const ros::Time &stamp)
Definition: line_segment_collector.h:122
jsk_pcl_ros::LineSegmentCluster::addLineSegmentEWMA
virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau)
Definition: line_segment_collector_nodelet.cpp:53
_2
boost::arg< 2 > _2
pcl_conversions::convertToPCLModelCoefficients
std::vector< pcl::ModelCoefficients::Ptr > convertToPCLModelCoefficients(const std::vector< PCLModelCoefficientMsg > &coefficients)
jsk_pcl_ros::LineSegmentCluster::LineSegmentCluster
LineSegmentCluster()
Definition: line_segment_collector_nodelet.cpp:45
_3
boost::arg< 3 > _3
boost::shared_ptr
i
int i
jsk_pcl_ros::LineSegmentCluster
Definition: line_segment_collector.h:92
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::LineSegmentCollector::sub_indices_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
Definition: line_segment_collector.h:186
jsk_pcl_ros::LineSegmentCollector::subscribe
virtual void subscribe()
Definition: line_segment_collector_nodelet.cpp:183
jsk_pcl_ros::LineSegmentCollector::segments_buffer_
TimeStampedVector< LineSegment::Ptr > segments_buffer_
Definition: line_segment_collector.h:205
jsk_pcl_ros::LineSegmentCollector::lookupNearestSegment
virtual LineSegmentCluster::Ptr lookupNearestSegment(LineSegment::Ptr segment)
Definition: line_segment_collector_nodelet.cpp:247
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
line_segment_collector.h
jsk_pcl_ros::LineSegmentCollector::indices_buffer_
TimeStampedVector< jsk_recognition_msgs::ClusterPointIndices::ConstPtr > indices_buffer_
Definition: line_segment_collector.h:203
jsk_pcl_ros::LineSegmentCluster::getRawPoints
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getRawPoints()
Definition: line_segment_collector_nodelet.cpp:80
jsk_pcl_ros::LineSegmentCollector::ROTATION_TILT_TWO_WAY
@ ROTATION_TILT_TWO_WAY
Definition: line_segment_collector.h:148
jsk_pcl_ros::LineSegmentCollector::coefficients_buffer_
TimeStampedVector< jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr > coefficients_buffer_
Definition: line_segment_collector.h:204
jsk_pcl_ros::LineSegmentCollector::unsubscribe
virtual void unsubscribe()
Definition: line_segment_collector_nodelet.cpp:196
jsk_pcl_ros::LineSegmentCollector::outlier_threshold_
double outlier_threshold_
Definition: line_segment_collector.h:213
jsk_pcl_ros::LineSegmentCollector::cleanupBuffers
virtual void cleanupBuffers(const ros::Time &stamp)
Definition: line_segment_collector_nodelet.cpp:204
jsk_pcl_ros::LineSegmentCollector::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: line_segment_collector.h:185
ros::Subscriber::shutdown
void shutdown()
jsk_pcl_ros::LineSegmentCluster::segments_
std::vector< LineSegment::Ptr > segments_
Definition: line_segment_collector.h:142
jsk_pcl_ros::LineSegmentCollector::collectFromBuffers
virtual void collectFromBuffers(const std_msgs::Header &header, std::vector< LineSegment::Ptr > new_segments)
Definition: line_segment_collector_nodelet.cpp:279
jsk_pcl_ros::LineSegmentCollector::time_range_
jsk_recognition_msgs::TimeRange::ConstPtr time_range_
Definition: line_segment_collector.h:209
jsk_pcl_ros::LineSegmentCluster::Ptr
boost::shared_ptr< LineSegmentCluster > Ptr
Definition: line_segment_collector.h:127
pcl_conversions::convertToPCLPointIndices
std::vector< pcl::PointIndices::Ptr > convertToPCLPointIndices(const std::vector< PCLIndicesMsg > &cluster_indices)
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::LineSegmentCollector::pub_polygons_
ros::Publisher pub_polygons_
Definition: line_segment_collector.h:191
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_pcl_ros::LineSegmentCollector::pub_point_cloud_
ros::Publisher pub_point_cloud_
Definition: line_segment_collector.h:188
cloud
cloud
jsk_pcl_ros::LineSegmentCluster::isEmpty
virtual bool isEmpty()
Definition: line_segment_collector_nodelet.cpp:121
jsk_pcl_ros::LineSegmentCluster::removeBefore
virtual void removeBefore(const ros::Time &stamp)
Definition: line_segment_collector_nodelet.cpp:85
jsk_pcl_ros::LineSegmentCollector::segment_connect_normal_threshold_
double segment_connect_normal_threshold_
Definition: line_segment_collector.h:207
class_list_macros.h
jsk_pcl_ros::LineSegmentCollector::collect
virtual void collect(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &indices_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: line_segment_collector_nodelet.cpp:352
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::LineSegmentCollector::publishResult
virtual void publishResult(const std_msgs::Header &header, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, std::vector< pcl::ModelCoefficients::Ptr > all_coefficients, std::vector< pcl::PointIndices::Ptr > all_indices)
Definition: line_segment_collector_nodelet.cpp:319
jsk_pcl_ros::LineSegmentCollector::segment_clusters_
std::vector< LineSegmentCluster::Ptr > segment_clusters_
Definition: line_segment_collector.h:206
jsk_pcl_ros::LineSegmentCollector::rotate_type_
RotateType rotate_type_
Definition: line_segment_collector.h:201
Vector3< float >
jsk_pcl_ros::LineSegmentCollector::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: line_segment_collector.h:184
jsk_pcl_ros::LineSegmentCluster::delta_
Eigen::Vector3f delta_
Definition: line_segment_collector.h:141
jsk_pcl_ros::LineSegmentCollector::pub_inliers_
ros::Publisher pub_inliers_
Definition: line_segment_collector.h:189
_1
boost::arg< 1 > _1
jsk_pcl_ros::LineSegmentCollector::mutex_
boost::mutex mutex_
Definition: line_segment_collector.h:183
pcl_conversions::convertToROSModelCoefficients
std::vector< PCLModelCoefficientMsg > convertToROSModelCoefficients(const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std_msgs::Header &header)
jsk_pcl_ros::LineSegmentCollector::pointclouds_buffer_
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > pointclouds_buffer_
Definition: line_segment_collector.h:202
pcl_conversion_util.h
jsk_pcl_ros::LineSegmentCluster::points_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
Definition: line_segment_collector.h:143
message_filters::Subscriber::subscribe
void subscribe()
jsk_pcl_ros::LineSegmentCollector::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: line_segment_collector.h:187
jsk_pcl_ros::LineSegmentCollector::debug_pub_inliers_before_plane_
ros::Publisher debug_pub_inliers_before_plane_
Definition: line_segment_collector.h:192
PointCloud
sensor_msgs::PointCloud2 PointCloud
nodelet::Nodelet
jsk_pcl_ros::LineSegmentCollector::ROTATION_TILT
@ ROTATION_TILT
Definition: line_segment_collector.h:148
ros::Time
jsk_pcl_ros::LineSegmentCollector::Config
jsk_pcl_ros::LineSegmentCollectorConfig Config
Definition: line_segment_collector.h:150
jsk_pcl_ros::LineSegmentCollector::pub_coefficients_
ros::Publisher pub_coefficients_
Definition: line_segment_collector.h:190
jsk_pcl_ros::LineSegment
Definition: line_segment_detector.h:91
pcl_util.h
dump_depth_error.f
f
Definition: dump_depth_error.py:39
jsk_pcl_ros::LineSegmentCluster::getPoints
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getPoints()
Definition: line_segment_collector_nodelet.cpp:75
jsk_pcl_ros::LineSegmentCollector::ewma_tau_
double ewma_tau_
Definition: line_segment_collector.h:208
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros::LineSegmentCollector
Definition: line_segment_collector.h:138
jsk_pcl_ros::LineSegmentCollector::ROTATION_SPINDLE
@ ROTATION_SPINDLE
Definition: line_segment_collector.h:148
jsk_pcl_ros::LineSegmentCollector::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: line_segment_collector.h:193
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::LineSegmentCollector, nodelet::Nodelet)
pcl_conversions::convertToROSPointIndices
std::vector< PCLIndicesMsg > convertToROSPointIndices(const std::vector< pcl::PointIndices > cluster_indices, const std_msgs::Header &header)
jsk_pcl_ros::LineSegmentCollector::~LineSegmentCollector
virtual ~LineSegmentCollector()
Definition: line_segment_collector_nodelet.cpp:164
config
config
jsk_pcl_ros::LineSegmentCluster::raw_points_
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
Definition: line_segment_collector.h:144
jsk_pcl_ros::LineSegmentCollector::triggerCallback
virtual void triggerCallback(const jsk_recognition_msgs::TimeRange::ConstPtr &trigger)
Definition: line_segment_collector_nodelet.cpp:223
jsk_pcl_ros::LineSegmentCollector::publishBeforePlaneSegmentation
virtual void publishBeforePlaneSegmentation(const std_msgs::Header &header, const pcl::PointCloud< pcl::PointXYZ >::Ptr cloud, const std::vector< pcl::PointIndices::Ptr > &connected_indices)
Definition: line_segment_collector_nodelet.cpp:231
jsk_pcl_ros::LineSegmentCollector::onInit
virtual void onInit()
Definition: line_segment_collector_nodelet.cpp:126


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