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 
39 
41 
42 #ifndef LASER_SCAN_LASERPROCESSOR_HH
43 #define LASER_SCAN_LASERPROCESSOR_HH
44 
45 #include <unistd.h>
46 #include <math.h>
47 #include "sensor_msgs/LaserScan.h"
48 #include "sensor_msgs/PointCloud.h"
49 #include "geometry_msgs/Point.h"
50 
51 #include <list>
52 #include <set>
53 #include <vector>
54 #include <map>
55 #include <utility>
56 #include <algorithm>
57 
58 #include "tf/transform_datatypes.h"
59 
60 namespace laser_processor
61 {
63 class Sample
64 {
65 public:
66  int index;
67  float range;
68  float intensity;
69  float x;
70  float y;
71 
72  static Sample* Extract(int ind, const sensor_msgs::LaserScan& scan);
73 
74 private:
75  Sample() {};
76 };
77 
80 {
82 
83  inline bool operator()(const Sample* a, const Sample* b)
84  {
85  return (a->index < b->index);
86  }
87 };
88 
89 
91 class SampleSet : public std::set<Sample*, CompareSample>
92 {
93 public:
94  SampleSet() {}
95 
97  {
98  clear();
99  }
100 
101  void clear();
102 
103  void appendToCloud(sensor_msgs::PointCloud& cloud, int r = 0, int g = 0, int b = 0);
104 
105  tf::Point center();
106 };
107 
109 class ScanMask
110 {
112 
113  bool filled;
114  float angle_min;
115  float angle_max;
116  uint32_t size;
117 
118 public:
119 
120  ScanMask() : filled(false), angle_min(0), angle_max(0), size(0) { }
121 
122  inline void clear()
123  {
124  mask_.clear();
125  filled = false;
126  }
127 
128  void addScan(sensor_msgs::LaserScan& scan);
129 
130  bool hasSample(Sample* s, float thresh);
131 };
132 
133 
134 
136 {
137  std::list<SampleSet*> clusters_;
138  sensor_msgs::LaserScan scan_;
139 
140 public:
141 
142  std::list<SampleSet*>& getClusters()
143  {
144  return clusters_;
145  }
146 
147  ScanProcessor(const sensor_msgs::LaserScan& scan, ScanMask& mask_, float mask_threshold = 0.03);
148 
149  ~ScanProcessor();
150 
151  void removeLessThan(uint32_t num);
152 
153  void splitConnected(float thresh);
154 };
155 };
156 
157 #endif
std::list< SampleSet * > clusters_
XmlRpcServer s
A namespace containing the laser processor helper classes.
sensor_msgs::LaserScan scan_
An ordered set of Samples.
A struct representing a single sample from the laser.
std::list< SampleSet * > & getClusters()
bool operator()(const Sample *a, const Sample *b)
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
The comparator allowing the creation of an ordered "SampleSet".
A mask for filtering out Samples based on range.


leg_detector
Author(s): Caroline Pantofaru
autogenerated on Fri Jun 7 2019 22:07:52