Fawkes API  Fawkes Development Version
laser-cluster-thread.h
1 
2 /***************************************************************************
3  * laser-cluster-thread.h - Thread to detect a cluster in 2D laser data
4  *
5  * Created: Sun Apr 21 01:17:09 2013
6  * Copyright 2011-2015 Tim Niemueller [www.niemueller.de]
7  ****************************************************************************/
8 
9 /* This program is free software; you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation; either version 2 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU Library General Public License for more details.
18  *
19  * Read the full text in the LICENSE.GPL file in the doc directory.
20  */
21 
22 #ifndef __PLUGINS_LASER_CLUSTER_LASER_CLUSTER_THREAD_H_
23 #define __PLUGINS_LASER_CLUSTER_LASER_CLUSTER_THREAD_H_
24 
25 // must be first for reliable ROS detection
26 #include <pcl/point_cloud.h>
27 #include <pcl/point_types.h>
28 
29 #include <core/threading/thread.h>
30 #include <aspect/clock.h>
31 #include <aspect/configurable.h>
32 #include <aspect/logging.h>
33 #include <aspect/blackboard.h>
34 #include <aspect/blocked_timing.h>
35 #include <aspect/tf.h>
36 #include <aspect/pointcloud.h>
37 
38 #include <Eigen/StdVector>
39 #include <pcl/segmentation/sac_segmentation.h>
40 
41 namespace fawkes {
42  class Position3DInterface;
43  class SwitchInterface;
44 #ifdef USE_TIMETRACKER
45  class TimeTracker;
46 #endif
47  class LaserClusterInterface;
48 }
49 
51 : public fawkes::Thread,
52  public fawkes::ClockAspect,
53  public fawkes::LoggingAspect,
59 {
60  public:
61  LaserClusterThread(std::string &cfg_name, std::string &cfg_prefix);
62  virtual ~LaserClusterThread();
63 
64  virtual void init();
65  virtual void loop();
66  virtual void finalize();
67 
68  private:
69  typedef pcl::PointXYZ PointType;
71  typedef Cloud::Ptr CloudPtr;
72  typedef Cloud::ConstPtr CloudConstPtr;
73 
74  typedef pcl::PointXYZRGB ColorPointType;
76  typedef ColorCloud::Ptr ColorCloudPtr;
77  typedef ColorCloud::ConstPtr ColorCloudConstPtr;
78 
79  typedef pcl::PointXYZL LabelPointType;
81  typedef LabelCloud::Ptr LabelCloudPtr;
82  typedef LabelCloud::ConstPtr LabelCloudConstPtr;
83 
84  private:
85  void set_position(fawkes::Position3DInterface *iface,
86  bool is_visible,
87  const Eigen::Vector4f &centroid = Eigen::Vector4f(0, 0, 0, 0),
88  const Eigen::Quaternionf &rotation = Eigen::Quaternionf(1, 0, 0, 0));
89 
90  float calc_line_length(CloudPtr cloud, pcl::PointIndices::Ptr inliers,
91  pcl::ModelCoefficients::Ptr coeff);
92 
93  /** Stub to see name in backtrace for easier debugging. @see Thread::run() */
94  protected: virtual void run() { Thread::run(); }
95 
96  private:
100  CloudConstPtr input_;
102  pcl::PointCloud<LabelPointType>::Ptr clusters_labeled_;
103 
104  pcl::SACSegmentation<PointType> seg_;
105 
106  std::vector<fawkes::Position3DInterface *> cluster_pos_ifs_;
107 
108  fawkes::SwitchInterface *switch_if_;
109  fawkes::LaserClusterInterface *config_if_;
110 
111  typedef enum {
112  SELECT_MIN_ANGLE,
113  SELECT_MIN_DIST
114  } selection_mode_t;
115 
116  std::string cfg_name_;
117  std::string cfg_prefix_;
118 
119  bool cfg_line_removal_;
120  float cfg_depth_filter_min_x_;
121  float cfg_depth_filter_max_x_;
122  unsigned int cfg_segm_max_iterations_;
123  float cfg_segm_distance_threshold_;
124  unsigned int cfg_segm_min_inliers_;
125  float cfg_segm_sample_max_dist_;
126  float cfg_line_min_length_;
127  float cfg_cluster_tolerance_;
128  unsigned int cfg_cluster_min_size_;
129  unsigned int cfg_cluster_max_size_;
130  std::string cfg_input_pcl_;
131  std::string cfg_result_frame_;
132  float cfg_bbox_min_x_;
133  float cfg_bbox_max_x_;
134  float cfg_bbox_min_y_;
135  float cfg_bbox_max_y_;
136  bool cfg_use_bbox_;
137  float cfg_switch_tolerance_;
138  float cfg_offset_x_;
139  float cfg_offset_y_;
140  float cfg_offset_z_;
141  selection_mode_t cfg_selection_mode_;
142  unsigned int cfg_max_num_clusters_;
143 
144  std::string output_cluster_name_;
145  std::string output_cluster_labeled_name_;
146 
147  float current_max_x_;
148 
149  unsigned int loop_count_;
150 
151  class ClusterInfo {
152  public:
153  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
154 
155  double angle;
156  double dist;
157  unsigned int index;
158  Eigen::Vector4f centroid;
159  };
160 
161 #ifdef USE_TIMETRACKER
162  fawkes::TimeTracker *tt_;
163  unsigned int tt_loopcount_;
164  unsigned int ttc_full_loop_;
165  unsigned int ttc_msg_proc_;
166  unsigned int ttc_extract_lines_;
167  unsigned int ttc_clustering_;
168 #endif
169 
170 };
171 
172 #endif
Thread aspect to access to BlackBoard.
Definition: blackboard.h:34
Thread aspect that allows to obtain the current time from the clock.
Definition: clock.h:36
LaserClusterInterface Fawkes BlackBoard Interface.
Fawkes library namespace.
Thread aspect to provide and access point clouds.
Definition: pointcloud.h:40
virtual void run()
Code to execute in the thread.
Definition: thread.cpp:939
Main thread of laser-cluster plugin.
Thread class encapsulation of pthreads.
Definition: thread.h:42
virtual void run()
Stub to see name in backtrace for easier debugging.
Thread aspect to access the transform system.
Definition: tf.h:42
Thread aspect to use blocked timing.
SwitchInterface Fawkes BlackBoard Interface.
Position3DInterface Fawkes BlackBoard Interface.
Time tracking utility.
Definition: tracker.h:38
Thread aspect to log output.
Definition: logging.h:35
Thread aspect to access configuration data.
Definition: configurable.h:35
RefPtr<> is a reference-counting shared smartpointer.
Definition: refptr.h:49