laserscanthread.h
Go to the documentation of this file.
1 
18 #ifndef LASERSCANTHREAD_H
19 #define LASERSCANTHREAD_H
20 #include <QThread>
21 #include <vector>
22 
23 #ifndef Q_MOC_RUN
24 #include <sensor_msgs/LaserScan.h>
25 #include <ros/ros.h>
26 #include <ros/init.h>
27 #include <Eigen/Dense>
28 #endif
29 
32 
33 using namespace std;
34 class LaserScanThread : public QThread
35 {
36  Q_OBJECT
37 public:
38  explicit LaserScanThread(Abstract_LaserScanner* scanner, double segmentation_lambda, double maxVarianceFilter, double maxAngleDeviation, double variationStep, int variationStepCount);
39  ~LaserScanThread();
40  unsigned int data_field_size;
41  float angle_spread;
43  double *dx;
44  double *data_raw;
45  double *data_avg;
46  double *data_filtered;
47  double *data_segments;
48  double *data_edges;
49  void stop();
50  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 protected:
52 
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;
57  //static const double sigma = 0.798;
58 
59  unsigned int stepNumber;
60  std::vector<float> segments;
61  std::vector<int> segmentsizes;
62  std::vector<int> segmentdistance;
63  double *averagedRanges;
64  double *rotatingAccumulationWindow[AVERAGINGWINDOW];
65  double *filteredRanges;
66  Eigen::Vector2d *coordinates;
67  std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > edgesfound;
68  double feld[2*GAUSSIANFIELDSIZE+1];
69  double gaussFactor;
70  double maxVarianceFilter = 0.15;
72  double variationStep = 0.006;
73  int variationStepCount = 2;
74  double segmentation_lambda = 1.5;
75 
76  double markersize = 0.02;
77 
79 
81 
86 
87  void calculateGaussianMatrix();
88  void launchSICK();
89  void run();
90 signals:
91  void valueChanged(); //Is called everytime new data is available
92  void trianglesFound(std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > *triangles); //Is called everytime a triangle is detected
93 
94 public slots:
95  void laserScanCallback(const sensor_msgs::LaserScan::ConstPtr& msg); //Is called everytime the laserscanner has new data
96 };
97 
98 
99 #endif // LASERSCANTHREAD_H
ros::Publisher scanDataPublisher
LinearApproximator * linearApproximator
unsigned int stepNumber
std::vector< int > segmentdistance
double maxAngleDeviation
std::vector< float > segments
double * data_segments
double * averagedRanges
Eigen::Vector2d * coordinates
double * filteredRanges
double * data_filtered
std::vector< int > segmentsizes
Abstract_LaserScanner * scanner
unsigned int data_field_size
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > edgesfound
ros::NodeHandle nh
ros::Publisher segmentBorderPublisher
ros::Publisher segmentDataPublisher


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43