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 
00072     static Sample* Extract(int ind, const sensor_msgs::LaserScan& scan);
00073 
00074   private:
00075      Sample() {};
00076   };
00077 
00079   struct CompareSample
00080   {
00081      CompareSample() {}
00082 
00083     inline bool operator() (const Sample* a, const Sample* b)
00084     {
00085       return (a->index <  b->index);
00086     }
00087   };
00088 
00089 
00091   class SampleSet : public std::set<Sample*, CompareSample>
00092   {
00093   public:
00094     SampleSet() {}
00095 
00096     ~SampleSet() { clear(); }
00097 
00098     void clear();
00099 
00100     void appendToCloud(sensor_msgs::PointCloud& cloud, int r = 0, int g = 0, int b = 0);
00101 
00102     tf::Point center();
00103   };
00104 
00106   class ScanMask
00107   {
00108     SampleSet mask_;
00109 
00110     bool     filled;
00111     float    angle_min;
00112     float    angle_max;
00113     uint32_t size;
00114 
00115   public:
00116 
00117     ScanMask() : filled(false), angle_min(0), angle_max(0), size(0) { }
00118 
00119     inline void clear() { mask_.clear(); filled = false; }
00120 
00121     void addScan(sensor_msgs::LaserScan& scan);
00122 
00123     bool hasSample(Sample* s, float thresh);
00124   };
00125 
00126 
00127 
00128   class ScanProcessor
00129   {
00130     std::list<SampleSet*> clusters_;
00131     sensor_msgs::LaserScan scan_;
00132 
00133   public:
00134 
00135     std::list<SampleSet*>& getClusters() { return clusters_; }
00136 
00137     ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
00138 
00139     ~ScanProcessor();
00140 
00141     void removeLessThan(uint32_t num);
00142 
00143     void splitConnected(float thresh);
00144   };
00145 };
00146 
00147 #endif