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)
63 for (SampleSet::iterator i = begin();
69 set<Sample*, CompareSample>::clear();
76 int rgb = (r << 16) | (g << 8) | b;
77 color_val = *(
float*) & (rgb);
79 for (iterator sample_iter = begin();
83 geometry_msgs::Point32 point;
84 point.x = (*sample_iter)->x;
85 point.y = (*sample_iter)->y;
88 cloud.points.push_back(point);
90 if (cloud.channels[0].name ==
"rgb")
91 cloud.channels[0].values.push_back(color_val);
99 for (iterator i = begin();
104 x_mean += ((*i)->x) / size();
105 y_mean += ((*i)->y) / size();
116 angle_min = scan.angle_min;
117 angle_max = scan.angle_max;
118 size = scan.ranges.size();
121 else if (angle_min != scan.angle_min ||
122 angle_max != scan.angle_max ||
123 size != scan.ranges.size())
125 throw std::runtime_error(
"laser_scan::ScanMask::addScan: inconsistantly sized scans added to mask");
128 for (uint32_t i = 0; i < scan.ranges.size(); i++)
134 SampleSet::iterator m = mask_.find(s);
136 if (m != mask_.end())
138 if ((*m)->range > s->
range)
162 SampleSet::iterator m = mask_.find(s);
163 if (m != mask_.end())
164 if (((*m)->range - thresh) < s->
range)
178 for (uint32_t i = 0; i < scan.ranges.size(); i++)
195 clusters_.push_back(cluster);
200 for (std::list<SampleSet*>::iterator c = clusters_.begin();
201 c != clusters_.end();
209 std::list<SampleSet*>::iterator c_iter = clusters_.begin();
210 while (c_iter != clusters_.end())
212 if ((*c_iter)->size() < num)
215 clusters_.erase(c_iter++);
228 std::list<SampleSet*> tmp_clusters;
230 std::list<SampleSet*>::iterator c_iter = clusters_.begin();
233 while (c_iter != clusters_.end())
236 while ((*c_iter)->size() > 0)
239 SampleSet::iterator s_first = (*c_iter)->begin();
242 std::list<Sample*> sample_queue;
243 sample_queue.push_back(*s_first);
245 (*c_iter)->erase(s_first);
248 std::list<Sample*>::iterator s_q = sample_queue.begin();
249 while (s_q != sample_queue.end())
251 int expand =
static_cast<int>(
asin(thresh / (*s_q)->range) / std::abs(scan_.angle_increment));
253 SampleSet::iterator s_rest = (*c_iter)->begin();
255 while ((s_rest != (*c_iter)->end() &&
256 (*s_rest)->index < (*s_q)->index + expand))
258 if ((*s_rest)->range - (*s_q)->range > thresh)
262 else if (
sqrt(
pow((*s_q)->x - (*s_rest)->x, 2.0f) +
pow((*s_q)->y - (*s_rest)->y, 2.0f)) < thresh)
264 sample_queue.push_back(*s_rest);
265 (*c_iter)->erase(s_rest++);
278 for (s_q = sample_queue.begin(); s_q != sample_queue.end(); s_q++)
282 tmp_clusters.push_back(c);
289 clusters_.erase(c_iter++);
292 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)