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


caster_app
Author(s): Ye Tian
autogenerated on Wed Dec 18 2019 03:34:44