laser_processor.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef LEG_DETECTOR_LASER_PROCESSOR_H
36 #define LEG_DETECTOR_LASER_PROCESSOR_H
37 
38 #include <unistd.h>
39 #include <math.h>
40 #include <sensor_msgs/LaserScan.h>
41 #include <sensor_msgs/PointCloud.h>
42 #include <geometry_msgs/Point.h>
43 
44 #include <list>
45 #include <set>
46 #include <vector>
47 #include <map>
48 #include <utility>
49 #include <algorithm>
50 
51 #include <tf/transform_datatypes.h>
52 
53 namespace laser_processor
54 {
56 class Sample
57 {
58 public:
59  int index;
60  float range;
61  float intensity;
62  float x;
63  float y;
64 
65  static Sample* Extract(int ind, const sensor_msgs::LaserScan& scan);
66 
67 private:
68  Sample() {}
69 };
70 
72 struct CompareSample
73 {
74  CompareSample() {}
75 
76  inline bool operator()(const Sample* a, const Sample* b)
77  {
78  return (a->index < b->index);
79  }
80 };
81 
82 
84 class SampleSet : public std::set<Sample*, CompareSample>
85 {
86 public:
87  SampleSet() {}
88 
89  ~SampleSet()
90  {
91  clear();
92  }
93 
94  void clear();
95 
96  void appendToCloud(sensor_msgs::PointCloud& cloud, int r = 0, int g = 0, int b = 0);
97 
98  tf::Point center();
99 };
100 
102 class ScanMask
103 {
105 
106  bool filled;
107  float angle_min;
108  float angle_max;
109  uint32_t size;
110 
111 public:
112  ScanMask() : filled(false), angle_min(0), angle_max(0), size(0) { }
113 
114  inline void clear()
115  {
117  filled = false;
118  }
119 
120  void addScan(sensor_msgs::LaserScan& scan);
121 
122  bool hasSample(Sample* s, float thresh);
123 };
124 
125 
126 
128 {
129  std::list<SampleSet*> clusters_;
130  sensor_msgs::LaserScan scan_;
131 
132 public:
133  std::list<SampleSet*>& getClusters()
134  {
135  return clusters_;
136  }
137 
138  ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
139 
141 
142  void removeLessThan(uint32_t num);
143 
144  void splitConnected(float thresh);
145 };
146 }; // namespace laser_processor
147 
148 #endif // LEG_DETECTOR_LASER_PROCESSOR_H
laser_processor::ScanMask::hasSample
bool hasSample(Sample *s, float thresh)
Definition: laser_processor.cpp:190
laser_processor::SampleSet::~SampleSet
~SampleSet()
Definition: laser_processor.h:121
laser_processor::ScanMask::angle_max
float angle_max
Definition: laser_processor.h:140
laser_processor::ScanProcessor::ScanProcessor
ScanProcessor(const sensor_msgs::LaserScan &scan, ScanMask &mask_, float mask_threshold=0.03)
Definition: laser_processor.cpp:204
laser_processor::SampleSet::clear
void clear()
Definition: laser_processor.cpp:93
laser_processor::SampleSet::appendToCloud
void appendToCloud(sensor_msgs::PointCloud &cloud, int r=0, int g=0, int b=0)
Definition: laser_processor.cpp:104
laser_processor::Sample
A struct representing a single sample from the laser.
Definition: laser_processor.h:88
laser_processor::Sample::x
float x
Definition: laser_processor.h:126
laser_processor::Sample::range
float range
Definition: laser_processor.h:124
laser_processor::ScanMask::mask_
SampleSet mask_
Definition: laser_processor.h:136
laser_processor::Sample::intensity
float intensity
Definition: laser_processor.h:125
laser_processor::SampleSet::center
tf::Point center()
Definition: laser_processor.cpp:127
laser_processor::ScanProcessor::splitConnected
void splitConnected(float thresh)
Definition: laser_processor.cpp:258
laser_processor::ScanMask::filled
bool filled
Definition: laser_processor.h:138
tf::Point
tf::Vector3 Point
laser_processor::Sample::Sample
Sample()
Definition: laser_processor.h:132
laser_processor::ScanMask
A mask for filtering out Samples based on range.
Definition: laser_processor.h:134
laser_processor::SampleSet
An ordered set of Samples.
Definition: laser_processor.h:116
laser_processor::ScanMask::addScan
void addScan(sensor_msgs::LaserScan &scan)
Definition: laser_processor.cpp:144
laser_processor::CompareSample
The comparator allowing the creation of an ordered "SampleSet".
Definition: laser_processor.h:104
laser_processor::ScanMask::angle_min
float angle_min
Definition: laser_processor.h:139
laser_processor::ScanProcessor::scan_
sensor_msgs::LaserScan scan_
Definition: laser_processor.h:162
transform_datatypes.h
laser_processor::ScanMask::size
uint32_t size
Definition: laser_processor.h:141
laser_processor::SampleSet::SampleSet
SampleSet()
Definition: laser_processor.h:119
laser_processor::ScanMask::ScanMask
ScanMask()
Definition: laser_processor.h:144
laser_processor::Sample::y
float y
Definition: laser_processor.h:127
laser_processor::CompareSample::CompareSample
CompareSample()
Definition: laser_processor.h:106
laser_processor::ScanProcessor::clusters_
std::list< SampleSet * > clusters_
Definition: laser_processor.h:161
laser_processor::CompareSample::operator()
bool operator()(const Sample *a, const Sample *b)
Definition: laser_processor.h:108
laser_processor
Definition: laser_processor.h:53
laser_processor::Sample::index
int index
Definition: laser_processor.h:123
laser_processor::Sample::Extract
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
Definition: laser_processor.cpp:76
laser_processor::ScanMask::clear
void clear()
Definition: laser_processor.h:146
laser_processor::ScanProcessor::removeLessThan
void removeLessThan(uint32_t num)
Definition: laser_processor.cpp:239
laser_processor::ScanProcessor
Definition: laser_processor.h:159
laser_processor::ScanProcessor::~ScanProcessor
~ScanProcessor()
Definition: laser_processor.cpp:230
laser_processor::ScanProcessor::getClusters
std::list< SampleSet * > & getClusters()
Definition: laser_processor.h:165


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:14