-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathpointcloud_preprocess.cc
189 lines (157 loc) · 6.57 KB
/
pointcloud_preprocess.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
#include "pointcloud_preprocess.h"
#include <glog/logging.h>
#include <execution>
namespace faster_lio {
void PointCloudPreprocess::Set(LidarType lid_type, double bld, int pfilt_num) {
lidar_type_ = lid_type;
blind_ = bld;
point_filter_num_ = pfilt_num;
}
void PointCloudPreprocess::Process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudType::Ptr &pcl_out) {
AviaHandler(msg);
*pcl_out = cloud_out_;
}
void PointCloudPreprocess::Process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudType::Ptr &pcl_out) {
switch (lidar_type_) {
case LidarType::OUST64:
Oust64Handler(msg);
break;
case LidarType::VELO32:
VelodyneHandler(msg);
break;
default:
LOG(ERROR) << "Error LiDAR Type";
break;
}
*pcl_out = cloud_out_;
}
void PointCloudPreprocess::AviaHandler(const livox_ros_driver::CustomMsg::ConstPtr &msg) {
cloud_out_.clear();
cloud_full_.clear();
int plsize = msg->point_num;
cloud_out_.reserve(plsize);
cloud_full_.resize(plsize);
std::vector<bool> is_valid_pt(plsize, false);
std::vector<uint> index(plsize - 1);
for (uint i = 0; i < plsize - 1; ++i) {
index[i] = i + 1; // 从1开始
}
std::for_each(std::execution::par_unseq, index.begin(), index.end(), [&](const uint &i) {
if ((msg->points[i].line < num_scans_) &&
((msg->points[i].tag & 0x30) == 0x10 || (msg->points[i].tag & 0x30) == 0x00)) {
if (i % point_filter_num_ == 0) {
cloud_full_[i].x = msg->points[i].x;
cloud_full_[i].y = msg->points[i].y;
cloud_full_[i].z = msg->points[i].z;
cloud_full_[i].intensity = msg->points[i].reflectivity;
cloud_full_[i].curvature =
msg->points[i].offset_time /
float(1000000); // use curvature as time of each laser points, curvature unit: ms
if ((abs(cloud_full_[i].x - cloud_full_[i - 1].x) > 1e-7) ||
(abs(cloud_full_[i].y - cloud_full_[i - 1].y) > 1e-7) ||
(abs(cloud_full_[i].z - cloud_full_[i - 1].z) > 1e-7) &&
(cloud_full_[i].x * cloud_full_[i].x + cloud_full_[i].y * cloud_full_[i].y +
cloud_full_[i].z * cloud_full_[i].z > (blind_ * blind_))) {
is_valid_pt[i] = true;
}
}
}
});
for (uint i = 1; i < plsize; i++) {
if (is_valid_pt[i]) {
cloud_out_.points.push_back(cloud_full_[i]);
}
}
}
void PointCloudPreprocess::Oust64Handler(const sensor_msgs::PointCloud2::ConstPtr &msg) {
cloud_out_.clear();
cloud_full_.clear();
pcl::PointCloud<ouster_ros::Point> pl_orig;
pcl::fromROSMsg(*msg, pl_orig);
int plsize = pl_orig.size();
cloud_out_.reserve(plsize);
for (int i = 0; i < pl_orig.points.size(); i++) {
if (i % point_filter_num_ != 0) continue;
double range = pl_orig.points[i].x * pl_orig.points[i].x + pl_orig.points[i].y * pl_orig.points[i].y +
pl_orig.points[i].z * pl_orig.points[i].z;
if (range < (blind_ * blind_)) continue;
Eigen::Vector3d pt_vec;
PointType added_pt;
added_pt.x = pl_orig.points[i].x;
added_pt.y = pl_orig.points[i].y;
added_pt.z = pl_orig.points[i].z;
added_pt.intensity = pl_orig.points[i].intensity;
added_pt.normal_x = 0;
added_pt.normal_y = 0;
added_pt.normal_z = 0;
added_pt.curvature = pl_orig.points[i].t / 1e6; // curvature unit: ms
cloud_out_.points.push_back(added_pt);
}
}
void PointCloudPreprocess::VelodyneHandler(const sensor_msgs::PointCloud2::ConstPtr &msg) {
cloud_out_.clear();
cloud_full_.clear();
pcl::PointCloud<velodyne_ros::Point> pl_orig;
pcl::fromROSMsg(*msg, pl_orig);
int plsize = pl_orig.points.size();
cloud_out_.reserve(plsize);
/*** These variables only works when no point timestamps given ***/
double omega_l = 3.61; // scan angular velocity
std::vector<bool> is_first(num_scans_, true);
std::vector<double> yaw_fp(num_scans_, 0.0); // yaw of first scan point
std::vector<float> yaw_last(num_scans_, 0.0); // yaw of last scan point
std::vector<float> time_last(num_scans_, 0.0); // last offset time
/*****************************************************************/
if (pl_orig.points[plsize - 1].time > 0) {
given_offset_time_ = true;
} else {
given_offset_time_ = false;
double yaw_first = atan2(pl_orig.points[0].y, pl_orig.points[0].x) * 57.29578;
double yaw_end = yaw_first;
int layer_first = pl_orig.points[0].ring;
for (uint i = plsize - 1; i > 0; i--) {
if (pl_orig.points[i].ring == layer_first) {
yaw_end = atan2(pl_orig.points[i].y, pl_orig.points[i].x) * 57.29578;
break;
}
}
}
for (int i = 0; i < plsize; i++) {
PointType added_pt;
added_pt.normal_x = 0;
added_pt.normal_y = 0;
added_pt.normal_z = 0;
added_pt.x = pl_orig.points[i].x;
added_pt.y = pl_orig.points[i].y;
added_pt.z = pl_orig.points[i].z;
added_pt.intensity = pl_orig.points[i].intensity;
added_pt.curvature = pl_orig.points[i].time * time_scale_; // curvature unit: ms
if (!given_offset_time_) {
int layer = pl_orig.points[i].ring;
double yaw_angle = atan2(added_pt.y, added_pt.x) * 57.2957;
if (is_first[layer]) {
yaw_fp[layer] = yaw_angle;
is_first[layer] = false;
added_pt.curvature = 0.0;
yaw_last[layer] = yaw_angle;
time_last[layer] = added_pt.curvature;
continue;
}
// compute offset time
if (yaw_angle <= yaw_fp[layer]) {
added_pt.curvature = (yaw_fp[layer] - yaw_angle) / omega_l;
} else {
added_pt.curvature = (yaw_fp[layer] - yaw_angle + 360.0) / omega_l;
}
if (added_pt.curvature < time_last[layer]) added_pt.curvature += 360.0 / omega_l;
yaw_last[layer] = yaw_angle;
time_last[layer] = added_pt.curvature;
}
if (i % point_filter_num_ == 0) {
if (added_pt.x * added_pt.x + added_pt.y * added_pt.y + added_pt.z * added_pt.z > (blind_ * blind_)) {
cloud_out_.points.push_back(added_pt);
}
}
}
}
} // namespace faster_lio