Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00039
00040
00041
00042 #ifndef LASER_SCAN_LASERPROCESSOR_HH
00043 #define LASER_SCAN_LASERPROCESSOR_HH
00044
00045 #include <unistd.h>
00046 #include <math.h>
00047 #include "sensor_msgs/LaserScan.h"
00048 #include "sensor_msgs/PointCloud.h"
00049 #include "geometry_msgs/Point.h"
00050
00051 #include <list>
00052 #include <set>
00053 #include <vector>
00054 #include <map>
00055 #include <utility>
00056 #include <algorithm>
00057
00058 #include "tf/transform_datatypes.h"
00059
00060 namespace laser_processor
00061 {
00063 class Sample
00064 {
00065 public:
00066 int index;
00067 float range;
00068 float intensity;
00069 float x;
00070 float y;
00071 float variation;
00072 int scans;
00073
00074 static Sample* Extract(int ind, const sensor_msgs::LaserScan& scan);
00075
00076 private:
00077 Sample() {};
00078 };
00079
00081 struct CompareSample
00082 {
00083 CompareSample() {}
00084
00085 inline bool operator() (const Sample* a, const Sample* b)
00086 {
00087 return (a->index < b->index);
00088 }
00089 };
00090
00091
00093 class SampleSet : public std::set<Sample*, CompareSample>
00094 {
00095 public:
00096 SampleSet() {}
00097
00098 ~SampleSet() { clear(); }
00099
00100 void clear();
00101
00102 void appendToCloud(sensor_msgs::PointCloud& cloud, int r = 0, int g = 0, int b = 0);
00103
00104 tf::Point center();
00105
00106 };
00107
00108
00109 class Background
00110 {
00111 SampleSet backgr_data;
00112
00113 bool filled;
00114 float angle_min;
00115 float angle_max;
00116 uint32_t size;
00117
00118 public:
00119 Background() : filled(false), angle_min(0), angle_max(0), size(0) { }
00120
00121 inline void clear() { backgr_data.clear(); filled = false; }
00122
00123 void addScan(sensor_msgs::LaserScan& scan, float treshhold);
00124
00125 bool isSamplebelongstoBackgrond(Sample* s, float thresh);
00126
00127 };
00128
00129
00131 class ScanMask
00132 {
00133 SampleSet mask_;
00134
00135 bool filled;
00136 float angle_min;
00137 float angle_max;
00138 uint32_t size;
00139
00140 public:
00141
00142 ScanMask() : filled(false), angle_min(0), angle_max(0), size(0) { }
00143
00144 inline void clear() { mask_.clear(); filled = false; }
00145
00146 void addScan(sensor_msgs::LaserScan& scan);
00147
00148 bool hasSample(Sample* s, float thresh);
00149 };
00150
00151
00152
00153 class ScanProcessor
00154 {
00155 std::list<SampleSet*> clusters_;
00156 sensor_msgs::LaserScan scan_;
00157
00158 public:
00159
00160 std::list<SampleSet*>& getClusters() { return clusters_; }
00161
00162 ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
00163 ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, Background& background_ , float mask_threshold = 0.03 , float background_treshhold = 0.03);
00164
00165 ~ScanProcessor();
00166
00167 void removeLessThan(uint32_t num);
00168
00169 void splitConnected(float thresh);
00170 };
00171 };
00172
00173 #endif