42 #ifndef LASER_SCAN_LASERPROCESSOR_HH 43 #define LASER_SCAN_LASERPROCESSOR_HH 47 #include "sensor_msgs/LaserScan.h" 48 #include "sensor_msgs/PointCloud.h" 49 #include "geometry_msgs/Point.h" 72 static Sample*
Extract(
int ind,
const sensor_msgs::LaserScan& scan);
91 class SampleSet :
public std::set<Sample*, CompareSample>
103 void appendToCloud(sensor_msgs::PointCloud& cloud,
int r = 0,
int g = 0,
int b = 0);
120 ScanMask() : filled(false), angle_min(0), angle_max(0), size(0) { }
128 void addScan(sensor_msgs::LaserScan& scan);
130 bool hasSample(
Sample*
s,
float thresh);
151 void removeLessThan(uint32_t num);
153 void splitConnected(
float thresh);
std::list< SampleSet * > clusters_
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.