line_segment_collector.h
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 
37 // the implementation is based on
38 // Line segment-based fast 3D plane extraction using nodding 2D laser rangender
39 // Su-Yong An, Lae-Kyoung Lee and Se-Young Oh,
40 // ,Robotica / FirstView Article / October 2014, pp 1 - 24
42 #ifndef JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_
43 #define JSK_PCL_ROS_LINE_SEGMENT_COLLECTOR_H_
44 
45 #include <jsk_topic_tools/diagnostic_nodelet.h>
46 #include <jsk_recognition_msgs/ClusterPointIndices.h>
47 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
48 #include <sensor_msgs/JointState.h>
50 #include <jsk_topic_tools/time_accumulator.h>
51 #include <jsk_pcl_ros/LineSegmentCollectorConfig.h>
52 #include <dynamic_reconfigure/server.h>
54 #include <jsk_recognition_msgs/PolygonArray.h>
55 #include <jsk_recognition_msgs/TimeRange.h>
56 
57 namespace jsk_pcl_ros
58 {
59 
60  class LineSegmentCluster
61  {
62  public:
65  virtual ~LineSegmentCluster() { };
66 
68  // update delta_ by EWMA(exponentially weighted moving agerage)
70  virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau);
71  virtual Eigen::Vector3f getDelta() { return delta_; }
72  virtual pcl::PointCloud<pcl::PointXYZ>::Ptr getPoints();
73  virtual pcl::PointCloud<pcl::PointXYZ>::Ptr getRawPoints();
74  virtual void removeBefore(const ros::Time& stamp);
75  virtual bool isEmpty();
76  protected:
77  Eigen::Vector3f delta_;
78  std::vector<LineSegment::Ptr> segments_;
79  pcl::PointCloud<pcl::PointXYZ>::Ptr points_;
80  pcl::PointCloud<pcl::PointXYZ>::Ptr raw_points_;
81  private:
82 
83  };
84 
85  template <class T>
86  class TimeStampedVector: public std::vector<T>
87  {
88  public:
89  typedef typename std::vector<T>::iterator iterator;
90  void removeBefore(const ros::Time& stamp)
91  {
92  for (iterator it = std::vector<T>::begin();
93  it != std::vector<T>::end();) {
94  if (((*it)->header.stamp - stamp) < ros::Duration(0.0)) {
95  it = this->erase(it);
96  }
97  else {
98  ++it;
99  }
100  }
101  }
102  protected:
103  private:
104  };
105 
106  class LineSegmentCollector: public jsk_topic_tools::DiagnosticNodelet
107  {
108  public:
109  LineSegmentCollector(): DiagnosticNodelet("LineSegmentCollector") { }
110  virtual ~LineSegmentCollector();
112  sensor_msgs::PointCloud2,
113  jsk_recognition_msgs::ClusterPointIndices,
114  jsk_recognition_msgs::ModelCoefficientsArray> SyncPolicy;
115  enum RotateType {
117  };
118  typedef jsk_pcl_ros::LineSegmentCollectorConfig Config;
119  protected:
121  // methods
123  virtual void onInit();
124  virtual void collectFromBuffers(const std_msgs::Header& header,
125  std::vector<LineSegment::Ptr> new_segments);
126  virtual void collect(
127  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
128  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
129  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
130  virtual void subscribe();
131  virtual void unsubscribe();
132  virtual void triggerCallback(
133  const jsk_recognition_msgs::TimeRange::ConstPtr& trigger);
134  virtual void cleanupBuffers(
135  const ros::Time& stamp);
136  virtual void publishBeforePlaneSegmentation(
137  const std_msgs::Header& header,
138  const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
139  const std::vector<pcl::PointIndices::Ptr>& connected_indices);
142  virtual void publishResult(
143  const std_msgs::Header& header,
144  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
145  std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
146  std::vector<pcl::PointIndices::Ptr> all_indices);
147  virtual void configCallback(Config &config, uint32_t level);
149  // ROS variables
162  jsk_topic_tools::TimeAccumulator connect_ac_;
164 
166  // parameters to collect pointclouds
168  std::string fixed_frame_id_;
174  std::vector<LineSegmentCluster::Ptr> segment_clusters_;
176  double ewma_tau_;
177  jsk_recognition_msgs::TimeRange::ConstPtr time_range_;
179  // plane estimation
181  double outlier_threshold_;
182 
183  private:
184 
185  };
186 }
187 
188 #endif
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
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
ros::Publisher
jsk_pcl_ros::LineSegmentCluster::LineSegmentCluster
LineSegmentCluster()
Definition: line_segment_collector_nodelet.cpp:45
boost::shared_ptr
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::LineSegmentCluster::getDelta
virtual Eigen::Vector3f getDelta()
Definition: line_segment_collector.h:135
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
jsk_pcl_ros::LineSegmentCollector::RotateType
RotateType
Definition: line_segment_collector.h:147
attention_pose_set.stamp
stamp
Definition: attention_pose_set.py:15
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
geo_util.h
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::fixed_frame_id_
std::string fixed_frame_id_
Definition: line_segment_collector.h:200
jsk_pcl_ros::LineSegmentCollector::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: line_segment_collector.h:185
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
jsk_pcl_ros::LineSegmentCollector::pub_polygons_
ros::Publisher pub_polygons_
Definition: line_segment_collector.h:191
jsk_pcl_ros::LineSegmentCollector::pub_point_cloud_
ros::Publisher pub_point_cloud_
Definition: line_segment_collector.h:188
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
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::LineSegmentCollector::segment_connect_normal_threshold_
double segment_connect_normal_threshold_
Definition: line_segment_collector.h:207
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::LineSegmentCollector::connect_ac_
jsk_topic_tools::TimeAccumulator connect_ac_
Definition: line_segment_collector.h:194
jsk_pcl_ros::LineSegment::Ptr
boost::shared_ptr< LineSegment > Ptr
Definition: line_segment_detector.h:126
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::LineSegmentCollector::LineSegmentCollector
LineSegmentCollector()
Definition: line_segment_collector.h:141
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
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
jsk_pcl_ros::TimeStampedVector::iterator
std::vector< T >::iterator iterator
Definition: line_segment_collector.h:121
jsk_pcl_ros::LineSegmentCollector::mutex_
boost::mutex mutex_
Definition: line_segment_collector.h:183
jsk_pcl_ros::LineSegmentCollector::pointclouds_buffer_
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > pointclouds_buffer_
Definition: line_segment_collector.h:202
jsk_pcl_ros::LineSegmentCluster::points_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
Definition: line_segment_collector.h:143
jsk_pcl_ros::LineSegmentCollector::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: line_segment_collector.h:187
line_segment_detector.h
jsk_pcl_ros::LineSegmentCollector::debug_pub_inliers_before_plane_
ros::Publisher debug_pub_inliers_before_plane_
Definition: line_segment_collector.h:192
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::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
jsk_pcl_ros::TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr >
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
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
message_filters::sync_policies::ExactTime
jsk_pcl_ros::LineSegmentCollector::~LineSegmentCollector
virtual ~LineSegmentCollector()
Definition: line_segment_collector_nodelet.cpp:164
jsk_pcl_ros::LineSegmentCluster::raw_points_
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
Definition: line_segment_collector.h:144
ros::Duration
jsk_pcl_ros::LineSegmentCollector::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
Definition: line_segment_collector.h:146
ros::Subscriber
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::LineSegmentCluster::~LineSegmentCluster
virtual ~LineSegmentCluster()
Definition: line_segment_collector.h:129
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