18 #ifndef LASERSCANTHREAD_H 19 #define LASERSCANTHREAD_H 24 #include <sensor_msgs/LaserScan.h> 27 #include <Eigen/Dense> 38 explicit LaserScanThread(
Abstract_LaserScanner* scanner,
double segmentation_lambda,
double maxVarianceFilter,
double maxAngleDeviation,
double variationStep,
int variationStepCount);
50 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 static constexpr
unsigned int GAUSSIANFIELDSIZE = 20;
54 static constexpr
unsigned int AVERAGINGWINDOW = 450;
55 static constexpr
unsigned int DETECTIONWINDOW = 10;
56 static constexpr
double sigma = 1.5;
64 double *rotatingAccumulationWindow[AVERAGINGWINDOW];
67 std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >
edgesfound;
68 double feld[2*GAUSSIANFIELDSIZE+1];
70 double maxVarianceFilter = 0.15;
72 double variationStep = 0.006;
73 int variationStepCount = 2;
74 double segmentation_lambda = 1.5;
76 double markersize = 0.02;
87 void calculateGaussianMatrix();
92 void trianglesFound(std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > *triangles);
95 void laserScanCallback(
const sensor_msgs::LaserScan::ConstPtr& msg);
99 #endif // LASERSCANTHREAD_H
ros::Publisher scanDataPublisher
LinearApproximator * linearApproximator
std::vector< int > segmentdistance
std::vector< float > segments
Eigen::Vector2d * coordinates
std::vector< int > segmentsizes
Abstract_LaserScanner * scanner
unsigned int data_field_size
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > edgesfound
ros::Publisher segmentBorderPublisher
ros::Publisher segmentDataPublisher