laser_processor.cpp
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 
36 
37 #include <stdexcept>
38 #include <list>
39 #include <set>
40 
41 namespace laser_processor
42 {
43 
44 Sample* Sample::Extract(int ind, const sensor_msgs::LaserScan& scan)
45 {
46  Sample* s = new Sample();
47 
48  s->index = ind;
49  s->range = scan.ranges[ind];
50  s->x = cos(scan.angle_min + ind * scan.angle_increment) * s->range;
51  s->y = sin(scan.angle_min + ind * scan.angle_increment) * s->range;
52  if (s->range > scan.range_min && s->range < scan.range_max)
53  return s;
54  else
55  {
56  delete s;
57  return NULL;
58  }
59 }
60 
62 {
63  for (SampleSet::iterator i = begin();
64  i != end();
65  i++)
66  {
67  delete *i;
68  }
69  set<Sample*, CompareSample>::clear();
70 }
71 
72 void SampleSet::appendToCloud(sensor_msgs::PointCloud& cloud, int r, int g, int b)
73 {
74  float color_val = 0;
75 
76  int rgb = (r << 16) | (g << 8) | b;
77  color_val = *(float*) & (rgb); // NOLINT(readability/casting)
78 
79  for (iterator sample_iter = begin();
80  sample_iter != end();
81  sample_iter++)
82  {
83  geometry_msgs::Point32 point;
84  point.x = (*sample_iter)->x;
85  point.y = (*sample_iter)->y;
86  point.z = 0;
87 
88  cloud.points.push_back(point);
89 
90  if (cloud.channels[0].name == "rgb")
91  cloud.channels[0].values.push_back(color_val);
92  }
93 }
94 
96 {
97  float x_mean = 0.0;
98  float y_mean = 0.0;
99  for (iterator i = begin();
100  i != end();
101  i++)
102 
103  {
104  x_mean += ((*i)->x) / size();
105  y_mean += ((*i)->y) / size();
106  }
107 
108  return tf::Point(x_mean, y_mean, 0.0);
109 }
110 
111 
112 void ScanMask::addScan(sensor_msgs::LaserScan& scan)
113 {
114  if (!filled)
115  {
116  angle_min = scan.angle_min;
117  angle_max = scan.angle_max;
118  size = scan.ranges.size();
119  filled = true;
120  }
121  else if (angle_min != scan.angle_min ||
122  angle_max != scan.angle_max ||
123  size != scan.ranges.size())
124  {
125  throw std::runtime_error("laser_scan::ScanMask::addScan: inconsistantly sized scans added to mask");
126  }
127 
128  for (uint32_t i = 0; i < scan.ranges.size(); i++)
129  {
130  Sample* s = Sample::Extract(i, scan);
131 
132  if (s != NULL)
133  {
134  SampleSet::iterator m = mask_.find(s);
135 
136  if (m != mask_.end())
137  {
138  if ((*m)->range > s->range)
139  {
140  delete *m;
141  mask_.erase(m);
142  mask_.insert(s);
143  }
144  else
145  {
146  delete s;
147  }
148  }
149  else
150  {
151  mask_.insert(s);
152  }
153  }
154  }
155 }
156 
157 
158 bool ScanMask::hasSample(Sample* s, float thresh)
159 {
160  if (s != NULL)
161  {
162  SampleSet::iterator m = mask_.find(s);
163  if (m != mask_.end())
164  if (((*m)->range - thresh) < s->range)
165  return true;
166  }
167  return false;
168 }
169 
170 
171 
172 ScanProcessor::ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold)
173 {
174  scan_ = scan;
175 
176  SampleSet* cluster = new SampleSet;
177 
178  for (uint32_t i = 0; i < scan.ranges.size(); i++)
179  {
180  Sample* s = Sample::Extract(i, scan);
181 
182  if (s != NULL)
183  {
184  if (!mask_.hasSample(s, mask_threshold))
185  {
186  cluster->insert(s);
187  }
188  else
189  {
190  delete s;
191  }
192  }
193  }
194 
195  clusters_.push_back(cluster);
196 }
197 
199 {
200  for (std::list<SampleSet*>::iterator c = clusters_.begin();
201  c != clusters_.end();
202  c++)
203  delete *c;
204 }
205 
206 void
208 {
209  std::list<SampleSet*>::iterator c_iter = clusters_.begin();
210  while (c_iter != clusters_.end())
211  {
212  if ((*c_iter)->size() < num)
213  {
214  delete *c_iter;
215  clusters_.erase(c_iter++);
216  }
217  else
218  {
219  ++c_iter;
220  }
221  }
222 }
223 
224 
225 void
227 {
228  std::list<SampleSet*> tmp_clusters;
229 
230  std::list<SampleSet*>::iterator c_iter = clusters_.begin();
231 
232  // For each cluster
233  while (c_iter != clusters_.end())
234  {
235  // Go through the entire list
236  while ((*c_iter)->size() > 0)
237  {
238  // Take the first element
239  SampleSet::iterator s_first = (*c_iter)->begin();
240 
241  // Start a new queue
242  std::list<Sample*> sample_queue;
243  sample_queue.push_back(*s_first);
244 
245  (*c_iter)->erase(s_first);
246 
247  // Grow until we get to the end of the queue
248  std::list<Sample*>::iterator s_q = sample_queue.begin();
249  while (s_q != sample_queue.end())
250  {
251  int expand = static_cast<int>(asin(thresh / (*s_q)->range) / std::abs(scan_.angle_increment));
252 
253  SampleSet::iterator s_rest = (*c_iter)->begin();
254 
255  while ((s_rest != (*c_iter)->end() &&
256  (*s_rest)->index < (*s_q)->index + expand))
257  {
258  if ((*s_rest)->range - (*s_q)->range > thresh)
259  {
260  break;
261  }
262  else if (sqrt(pow((*s_q)->x - (*s_rest)->x, 2.0f) + pow((*s_q)->y - (*s_rest)->y, 2.0f)) < thresh)
263  {
264  sample_queue.push_back(*s_rest);
265  (*c_iter)->erase(s_rest++);
266  break;
267  }
268  else
269  {
270  ++s_rest;
271  }
272  }
273  s_q++;
274  }
275 
276  // Move all the samples into the new cluster
277  SampleSet* c = new SampleSet;
278  for (s_q = sample_queue.begin(); s_q != sample_queue.end(); s_q++)
279  c->insert(*s_q);
280 
281  // Store the temporary clusters
282  tmp_clusters.push_back(c);
283  }
284 
285  // Now that c_iter is empty, we can delete
286  delete *c_iter;
287 
288  // And remove from the map
289  clusters_.erase(c_iter++);
290  }
291 
292  clusters_.insert(clusters_.begin(), tmp_clusters.begin(), tmp_clusters.end());
293 }
294 
295 } // namespace laser_processor
XmlRpcServer s
tf::Vector3 Point
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
bool hasSample(Sample *s, float thresh)
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
An ordered set of Samples.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
A struct representing a single sample from the laser.
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
void appendToCloud(sensor_msgs::PointCloud &cloud, int r=0, int g=0, int b=0)
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
A mask for filtering out Samples based on range.
void addScan(sensor_msgs::LaserScan &scan)
ScanProcessor(const sensor_msgs::LaserScan &scan, ScanMask &mask_, float mask_threshold=0.03)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Sun Feb 21 2021 03:56:50