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)
62 for (SampleSet::iterator i = begin();
68 set<Sample*, CompareSample>::clear();
75 int rgb = (r << 16) | (g << 8) | b;
76 color_val = *
reinterpret_cast<float*
>(&rgb);
78 for (iterator sample_iter = begin();
82 geometry_msgs::Point32 point;
83 point.x = (*sample_iter)->x;
84 point.y = (*sample_iter)->y;
87 cloud.points.push_back(point);
89 if (cloud.channels[0].name ==
"rgb")
90 cloud.channels[0].values.push_back(color_val);
98 for (iterator i = begin();
103 x_mean += ((*i)->x) /
size();
104 y_mean += ((*i)->y) /
size();
114 angle_min = scan.angle_min;
115 angle_max = scan.angle_max;
116 size = scan.ranges.size();
119 else if (angle_min != scan.angle_min ||
120 angle_max != scan.angle_max ||
121 size != scan.ranges.size())
123 throw std::runtime_error(
"laser_scan::ScanMask::addScan: inconsistantly sized scans added to mask");
126 for (uint32_t i = 0; i < scan.ranges.size(); i++)
132 SampleSet::iterator m = mask_.find(s);
134 if (m != mask_.end())
136 if ((*m)->range > s->
range)
159 SampleSet::iterator m = mask_.find(s);
160 if (m != mask_.end())
161 if (((*m)->range - thresh) < s->
range)
172 cluster->
header = scan.header;
174 for (uint32_t i = 0; i < scan.ranges.size(); i++)
191 clusters_.push_back(cluster);
196 for (std::list<SampleSet*>::iterator
c = clusters_.begin();
197 c != clusters_.end();
204 std::list<SampleSet*>::iterator c_iter = clusters_.begin();
205 while (c_iter != clusters_.end())
207 if ((*c_iter)->size() < num)
210 clusters_.erase(c_iter++);
221 std::list<SampleSet*> tmp_clusters;
223 std::list<SampleSet*>::iterator c_iter = clusters_.begin();
226 while (c_iter != clusters_.end())
229 while ((*c_iter)->size() > 0)
232 SampleSet::iterator s_first = (*c_iter)->begin();
235 std::list<Sample*> sample_queue;
236 sample_queue.push_back(*s_first);
238 (*c_iter)->erase(s_first);
241 std::list<Sample*>::iterator s_q = sample_queue.begin();
242 while (s_q != sample_queue.end())
244 int expand =
static_cast<int>(
asin(thresh / (*s_q)->range) / scan_.angle_increment);
246 SampleSet::iterator s_rest = (*c_iter)->begin();
248 while ((s_rest != (*c_iter)->end() &&
249 (*s_rest)->index < (*s_q)->index + expand))
251 if ((*s_rest)->range - (*s_q)->range > thresh)
255 else if (
sqrt(
pow((*s_q)->x - (*s_rest)->x, 2.0f) +
pow((*s_q)->y - (*s_rest)->y, 2.0f)) < thresh)
257 sample_queue.push_back(*s_rest);
258 (*c_iter)->erase(s_rest++);
271 c->
header = (*c_iter)->header;
272 for (s_q = sample_queue.begin(); s_q != sample_queue.end(); s_q++)
276 tmp_clusters.push_back(c);
283 clusters_.erase(c_iter++);
286 clusters_.insert(clusters_.begin(), tmp_clusters.begin(), tmp_clusters.end());
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
void splitConnected(float thresh)
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)
void removeLessThan(uint32_t num)
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)