Go to the documentation of this file.
35 #ifndef LEG_DETECTOR_LASER_PROCESSOR_H
36 #define LEG_DETECTOR_LASER_PROCESSOR_H
40 #include <sensor_msgs/LaserScan.h>
41 #include <sensor_msgs/PointCloud.h>
42 #include <geometry_msgs/Point.h>
65 static Sample*
Extract(
int ind,
const sensor_msgs::LaserScan& scan);
84 class SampleSet :
public std::set<Sample*, CompareSample>
96 void appendToCloud(sensor_msgs::PointCloud& cloud,
int r = 0,
int g = 0,
int b = 0);
120 void addScan(sensor_msgs::LaserScan& scan);
130 sensor_msgs::LaserScan
scan_;
148 #endif // LEG_DETECTOR_LASER_PROCESSOR_H
bool hasSample(Sample *s, float thresh)
ScanProcessor(const sensor_msgs::LaserScan &scan, ScanMask &mask_, float mask_threshold=0.03)
void appendToCloud(sensor_msgs::PointCloud &cloud, int r=0, int g=0, int b=0)
A struct representing a single sample from the laser.
void splitConnected(float thresh)
A mask for filtering out Samples based on range.
An ordered set of Samples.
void addScan(sensor_msgs::LaserScan &scan)
The comparator allowing the creation of an ordered "SampleSet".
sensor_msgs::LaserScan scan_
std::list< SampleSet * > clusters_
bool operator()(const Sample *a, const Sample *b)
static Sample * Extract(int ind, const sensor_msgs::LaserScan &scan)
void removeLessThan(uint32_t num)
std::list< SampleSet * > & getClusters()
leg_detector
Author(s): Caroline Pantofaru
autogenerated on Wed Mar 2 2022 00:45:14