lidar_utils.hpp
Go to the documentation of this file.
1 
3 
4 // Original Author of FLOAM: Wang Han
5 // Email wh200720041@gmail.com
6 // Homepage https://wanghan.pro
7 
8 #ifndef FLOAM__LIDAR_UTILS_HPP_
9 #define FLOAM__LIDAR_UTILS_HPP_
10 #include <pcl/features/organized_edge_detection.h>
11 #include <pcl/features/integral_image_normal.h>
12 #include <pcl/point_cloud.h>
13 
14 namespace floam
15 {
16 namespace lidar
17 {
18 
19 enum Type {
23 };
24 
25 struct Distance {
26  double max{100.0};
27  double min{0.0};
28 };
29 
30 struct Limits {
32  int sectors;
33  double edgeThreshold;
34 };
35 
37  uint16_t vertical{1};
38  uint16_t horizontal{1};
39 };
40 
41 struct FOV {
42  double vertical{30.0};
43  double horizontal{120.0};
44 };
45 
46 struct Settings {
47  std::string frameId;
49  FOV fov; // degrees
52 };
53 
54 class Scanner {
55 public:
56  Scanner();
57  ~Scanner();
58  int lines{0};
59  int skipPoints{50};
60  int searchK{10};
61  double searchRadius{0.25};
62  double period{0.0};
63  double scan_rate{0.0};
65 };
66 
67 class Imager {
68 public:
69  Imager();
70  ~Imager();
71  double framerate{0.0};
73 };
74 
75 struct Total {
76  double time{0.0};
77  int frames{0};
78 };
79 
80 struct Surface {
81  pcl::PointCloud<pcl::PointXYZ>::Ptr points;
82  pcl::PointCloud<pcl::Normal>::Ptr normals;
83 };
84 
85 struct Edge {
86  pcl::PointCloud<pcl::PointXYZ>::Ptr points;
87  pcl::PointCloud<pcl::Label>::Ptr labels;
88 };
89 
90 //points covariance class
91 class Double2d{
92 public:
93  int id;
94  double diffTotal;
95  double diffLeft;
96  double diffRight;
97  Double2d(
98  const int & id,
99  const double & diffTotal,
100  const double & diffLeft,
101  const double & diffRight);
102 };
103 
104 //points info class
106 public:
107  int layer;
108  double time;
109  PointsInfo(int layer_in, double time_in);
110 };
111 
112 } // namespace lidar
113 } // namespace floam
114 
115 #endif // FLOAM__LIDAR_UTILS_HPP_
pcl::PointCloud< pcl::PointXYZ >::Ptr points
Definition: lidar_utils.hpp:86
pcl::PointCloud< pcl::PointXYZ >::Ptr points
Definition: lidar_utils.hpp:81
pcl::PointCloud< pcl::Normal >::Ptr normals
Definition: lidar_utils.hpp:82
AngularResolution angular
Definition: lidar_utils.hpp:50
Major rewrite Author: Evan Flynn.
Definition: lidar.hpp:15
pcl::PointCloud< pcl::Label >::Ptr labels
Definition: lidar_utils.hpp:87


floam
Author(s): Han Wang
autogenerated on Mon Feb 28 2022 22:25:11