laser_processor.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
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; // used only in the class Background
00072     int scans; // used only in the class Background to to averaging contains the number of scans that have gone into this scan
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;  // indicates if there is any data inside
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


srs_leg_detector
Author(s): Alex Noyvirt
autogenerated on Mon Oct 6 2014 09:16:48