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/o2r 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 
46 #include <jsk_recognition_msgs/ClusterPointIndices.h>
47 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
48 #include <sensor_msgs/JointState.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 
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;
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 
107  {
108  public:
109  LineSegmentCollector(): DiagnosticNodelet("LineSegmentCollector") { }
111  sensor_msgs::PointCloud2,
112  jsk_recognition_msgs::ClusterPointIndices,
113  jsk_recognition_msgs::ModelCoefficientsArray> SyncPolicy;
114  enum RotateType {
115  ROTATION_SPINDLE, ROTATION_TILT, ROTATION_TILT_TWO_WAY
116  };
117  typedef jsk_pcl_ros::LineSegmentCollectorConfig Config;
118  protected:
120  // methods
122  virtual void onInit();
123  virtual void collectFromBuffers(const std_msgs::Header& header,
124  std::vector<LineSegment::Ptr> new_segments);
125  virtual void collect(
126  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
127  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
128  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg);
129  virtual void subscribe();
130  virtual void unsubscribe();
131  virtual void triggerCallback(
132  const jsk_recognition_msgs::TimeRange::ConstPtr& trigger);
133  virtual void cleanupBuffers(
134  const ros::Time& stamp);
135  virtual void publishBeforePlaneSegmentation(
136  const std_msgs::Header& header,
137  const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
138  const std::vector<pcl::PointIndices::Ptr>& connected_indices);
139  virtual LineSegmentCluster::Ptr lookupNearestSegment(
140  LineSegment::Ptr segment);
141  virtual void publishResult(
142  const std_msgs::Header& header,
143  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
144  std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
145  std::vector<pcl::PointIndices::Ptr> all_indices);
146  virtual void configCallback(Config &config, uint32_t level);
148  // ROS variables
163 
165  // parameters to collect pointclouds
167  std::string fixed_frame_id_;
173  std::vector<LineSegmentCluster::Ptr> segment_clusters_;
175  double ewma_tau_;
176  jsk_recognition_msgs::TimeRange::ConstPtr time_range_;
178  // plane estimation
181 
182  private:
183 
184  };
185 }
186 
187 #endif
void collect()
void removeBefore(const ros::Time &stamp)
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getRawPoints()
virtual void addLineSegmentEWMA(LineSegment::Ptr segment, const double tau)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
virtual void removeBefore(const ros::Time &stamp)
virtual Eigen::Vector3f getDelta()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::vector< LineSegment::Ptr > segments_
jsk_pcl_ros::LineSegmentCollectorConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::ModelCoefficientsArray > SyncPolicy
TimeStampedVector< jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr > coefficients_buffer_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
void subscribe()
jsk_topic_tools::TimeAccumulator connect_ac_
std::vector< LineSegmentCluster::Ptr > segment_clusters_
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
TimeStampedVector< jsk_recognition_msgs::ClusterPointIndices::ConstPtr > indices_buffer_
jsk_recognition_msgs::TimeRange::ConstPtr time_range_
boost::mutex mutex
global mutex.
std::vector< T >::iterator iterator
TimeStampedVector< sensor_msgs::PointCloud2::ConstPtr > pointclouds_buffer_
TimeStampedVector< LineSegment::Ptr > segments_buffer_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
boost::shared_ptr< LineSegmentCluster > Ptr
pcl::PointCloud< pcl::PointXYZ >::Ptr raw_points_
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr getPoints()


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47