Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Typedefs
Enumerations
Enumerator
Classes
Class List
Class Hierarchy
Class Members
All
_
a
c
d
e
f
g
h
i
l
m
n
o
p
s
t
u
v
~
Functions
a
c
d
e
g
h
i
l
o
p
s
u
~
Variables
_
a
c
d
e
f
h
i
l
m
n
p
s
t
v
Typedefs
Files
File List
File Members
All
Functions
Macros
include
floam
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
{
20
SCANNER_ROTATING
= 0,
21
SCANNER_MEMS
,
22
IMAGER
,
23
};
24
25
struct
Distance
{
26
double
max
{100.0};
27
double
min
{0.0};
28
};
29
30
struct
Limits
{
31
Distance
distance
;
32
int
sectors
;
33
double
edgeThreshold
;
34
};
35
36
struct
AngularResolution
{
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
;
48
Type
type
;
49
FOV
fov
;
// degrees
50
AngularResolution
angular
;
// degrees
51
Limits
limits
;
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};
64
Settings
common
;
65
};
66
67
class
Imager
{
68
public
:
69
Imager
();
70
~Imager
();
71
double
framerate
{0.0};
72
Settings
common
;
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
105
class
PointsInfo
{
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_
floam::lidar::Edge::labels
pcl::PointCloud< pcl::Label >::Ptr labels
Definition:
lidar_utils.hpp:87
floam::lidar::Double2d::Double2d
Double2d(const int &id, const double &diffTotal, const double &diffLeft, const double &diffRight)
Definition:
lidar_utils.cpp:31
floam::lidar::Scanner
Definition:
lidar_utils.hpp:54
floam::lidar::Surface
Definition:
lidar_utils.hpp:80
floam::lidar::FOV::vertical
double vertical
Definition:
lidar_utils.hpp:42
floam::lidar::AngularResolution::vertical
uint16_t vertical
Definition:
lidar_utils.hpp:37
floam::lidar::Double2d::id
int id
Definition:
lidar_utils.hpp:93
floam::lidar::Scanner::searchK
int searchK
Definition:
lidar_utils.hpp:60
floam::lidar::Surface::points
pcl::PointCloud< pcl::PointXYZ >::Ptr points
Definition:
lidar_utils.hpp:81
floam::lidar::Scanner::Scanner
Scanner()
Definition:
lidar_utils.cpp:11
floam::lidar::Scanner::searchRadius
double searchRadius
Definition:
lidar_utils.hpp:61
floam::lidar::Scanner::period
double period
Definition:
lidar_utils.hpp:62
floam::lidar::Limits::sectors
int sectors
Definition:
lidar_utils.hpp:32
floam::lidar::Limits::distance
Distance distance
Definition:
lidar_utils.hpp:31
floam::lidar::SCANNER_MEMS
@ SCANNER_MEMS
Definition:
lidar_utils.hpp:21
floam::lidar::SCANNER_ROTATING
@ SCANNER_ROTATING
Definition:
lidar_utils.hpp:20
floam::lidar::Scanner::lines
int lines
Definition:
lidar_utils.hpp:58
floam::lidar::Limits::edgeThreshold
double edgeThreshold
Definition:
lidar_utils.hpp:33
floam::lidar::Imager::~Imager
~Imager()
Definition:
lidar_utils.cpp:26
floam::lidar::IMAGER
@ IMAGER
Definition:
lidar_utils.hpp:22
floam::lidar::Total
Definition:
lidar_utils.hpp:75
floam::lidar::Scanner::scan_rate
double scan_rate
Definition:
lidar_utils.hpp:63
floam::lidar::Double2d::diffTotal
double diffTotal
Definition:
lidar_utils.hpp:94
floam::lidar::Total::time
double time
Definition:
lidar_utils.hpp:76
floam::lidar::Settings::angular
AngularResolution angular
Definition:
lidar_utils.hpp:50
floam::lidar::Double2d::diffLeft
double diffLeft
Definition:
lidar_utils.hpp:95
floam::lidar::Imager::Imager
Imager()
Definition:
lidar_utils.cpp:21
floam::lidar::PointsInfo::layer
int layer
Definition:
lidar_utils.hpp:107
floam::lidar::PointsInfo::PointsInfo
PointsInfo(int layer_in, double time_in)
Definition:
lidar_utils.cpp:43
floam::lidar::Edge
Definition:
lidar_utils.hpp:85
floam::lidar::Double2d::diffRight
double diffRight
Definition:
lidar_utils.hpp:96
floam::lidar::Double2d
Definition:
lidar_utils.hpp:91
floam::lidar::Settings::fov
FOV fov
Definition:
lidar_utils.hpp:49
floam::lidar::Scanner::skipPoints
int skipPoints
Definition:
lidar_utils.hpp:59
floam::lidar::FOV
Definition:
lidar_utils.hpp:41
floam::lidar::Settings::type
Type type
Definition:
lidar_utils.hpp:48
floam::lidar::Settings::frameId
std::string frameId
Definition:
lidar_utils.hpp:47
floam::lidar::Distance::min
double min
Definition:
lidar_utils.hpp:27
floam::lidar::Distance
Definition:
lidar_utils.hpp:25
floam::lidar::Imager::common
Settings common
Definition:
lidar_utils.hpp:72
floam::lidar::Scanner::~Scanner
~Scanner()
Definition:
lidar_utils.cpp:16
floam::lidar::Distance::max
double max
Definition:
lidar_utils.hpp:26
floam::lidar::AngularResolution
Definition:
lidar_utils.hpp:36
floam::lidar::Settings
Definition:
lidar_utils.hpp:46
floam::lidar::Total::frames
int frames
Definition:
lidar_utils.hpp:77
floam::lidar::PointsInfo
Definition:
lidar_utils.hpp:105
floam::lidar::Type
Type
Definition:
lidar_utils.hpp:19
floam::lidar::AngularResolution::horizontal
uint16_t horizontal
Definition:
lidar_utils.hpp:38
floam::lidar::Settings::limits
Limits limits
Definition:
lidar_utils.hpp:51
floam::lidar::Scanner::common
Settings common
Definition:
lidar_utils.hpp:64
floam::lidar::FOV::horizontal
double horizontal
Definition:
lidar_utils.hpp:43
floam::lidar::Imager
Definition:
lidar_utils.hpp:67
floam
Major rewrite Author: Evan Flynn.
Definition:
lidar.hpp:15
floam::lidar::PointsInfo::time
double time
Definition:
lidar_utils.hpp:108
floam::lidar::Surface::normals
pcl::PointCloud< pcl::Normal >::Ptr normals
Definition:
lidar_utils.hpp:82
floam::lidar::Limits
Definition:
lidar_utils.hpp:30
floam::lidar::Imager::framerate
double framerate
Definition:
lidar_utils.hpp:71
floam::lidar::Edge::points
pcl::PointCloud< pcl::PointXYZ >::Ptr points
Definition:
lidar_utils.hpp:86
floam
Author(s): Han Wang
autogenerated on Wed Mar 2 2022 00:23:09