forked from autowarefoundation/autoware_universe
-
Notifications
You must be signed in to change notification settings - Fork 34
/
Copy pathtest_postprocess_kernel.cpp
368 lines (312 loc) · 14 KB
/
test_postprocess_kernel.cpp
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
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "test_postprocess_kernel.hpp"
#include <gtest/gtest.h>
#include <cmath>
#include <memory>
#include <vector>
namespace centerpoint
{
void PostprocessKernelTest::SetUp()
{
cudaStreamCreate(&stream_);
constexpr std::size_t class_size{5};
constexpr std::size_t point_feature_size{4};
const std::size_t cloud_capacity{2000000};
constexpr std::size_t max_voxel_size{100000000};
const std::vector<double> point_cloud_range{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0};
const std::vector<double> voxel_size{0.32, 0.32, 10.0};
constexpr std::size_t downsample_factor{1};
constexpr std::size_t encoder_in_feature_size{9};
constexpr float score_threshold{0.35f};
constexpr float circle_nms_dist_threshold{0.5f};
const std::vector<double> yaw_norm_thresholds{0.5, 0.5, 0.5};
constexpr bool has_variance{false};
config_ptr_ = std::make_unique<centerpoint::CenterPointConfig>(
class_size, point_feature_size, cloud_capacity, max_voxel_size, point_cloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_thresholds, has_variance);
postprocess_cuda_ptr_ = std::make_unique<PostProcessCUDA>(*config_ptr_);
const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_;
head_out_heatmap_d_ = cuda::make_unique<float[]>(grid_xy_size * config_ptr_->class_size_);
head_out_offset_d_ =
cuda::make_unique<float[]>(grid_xy_size * config_ptr_->head_out_offset_size_);
head_out_z_d_ = cuda::make_unique<float[]>(grid_xy_size * config_ptr_->head_out_z_size_);
head_out_dim_d_ = cuda::make_unique<float[]>(grid_xy_size * config_ptr_->head_out_dim_size_);
head_out_rot_d_ = cuda::make_unique<float[]>(grid_xy_size * config_ptr_->head_out_rot_size_);
head_out_vel_d_ = cuda::make_unique<float[]>(grid_xy_size * config_ptr_->head_out_vel_size_);
std::vector<float> heatmap_host_vector(grid_xy_size * config_ptr_->class_size_, 0.f);
std::fill(heatmap_host_vector.begin(), heatmap_host_vector.end(), -1e6);
cudaMemcpy(
head_out_heatmap_d_.get(), heatmap_host_vector.data(),
grid_xy_size * config_ptr_->head_out_offset_size_ * sizeof(float), cudaMemcpyHostToDevice);
cudaMemset(
head_out_offset_d_.get(), 0, grid_xy_size * config_ptr_->head_out_offset_size_ * sizeof(float));
cudaMemset(head_out_z_d_.get(), 0, grid_xy_size * config_ptr_->head_out_z_size_ * sizeof(float));
cudaMemset(
head_out_dim_d_.get(), 0, grid_xy_size * config_ptr_->head_out_dim_size_ * sizeof(float));
cudaMemset(
head_out_rot_d_.get(), 0, grid_xy_size * config_ptr_->head_out_rot_size_ * sizeof(float));
cudaMemset(
head_out_vel_d_.get(), 0, grid_xy_size * config_ptr_->head_out_vel_size_ * sizeof(float));
}
void PostprocessKernelTest::TearDown()
{
}
TEST_F(PostprocessKernelTest, EmptyTensorTest)
{
std::vector<Box3D> det_boxes3d;
postprocess_cuda_ptr_->generateDetectedBoxes3D_launch(
head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(),
head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_);
ASSERT_EQ(0, det_boxes3d.size());
}
TEST_F(PostprocessKernelTest, SingleDetectionTest)
{
std::vector<Box3D> det_boxes3d;
constexpr float detection_x = 70.f;
constexpr float detection_y = -38.4f;
constexpr float detection_z = 1.0;
const float detection_log_w = std::log(7.0);
const float detection_log_l = std::log(1.0);
const float detection_log_h = std::log(2.0);
constexpr float detection_yaw = M_PI_4;
const float detection_yaw_sin = std::sin(detection_yaw);
const float detection_yaw_cos = std::sin(detection_yaw);
constexpr float detection_vel_x = 5.0;
constexpr float detection_vel_y = -5.0;
const float idx =
((detection_x - config_ptr_->range_min_x_) /
(config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_));
const float idy =
((detection_y - config_ptr_->range_min_y_) /
(config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_));
const std::size_t index = config_ptr_->down_grid_size_x_ * std::floor(idy) + std::floor(idx);
const float detection_x_offset = idx - std::floor(idx);
const float detection_y_offset = idy - std::floor(idy);
// Set the values in the cuda tensor
const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_;
float score = 1.f;
cudaMemcpy(
&head_out_heatmap_d_[2 * grid_xy_size + index], &score, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[0 * grid_xy_size + index], &detection_x_offset, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[1 * grid_xy_size + index], &detection_y_offset, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_z_d_[0 * grid_xy_size + index], &detection_z, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[0 * grid_xy_size + index], &detection_log_w, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[1 * grid_xy_size + index], &detection_log_l, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[2 * grid_xy_size + index], &detection_log_h, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[0 * grid_xy_size + index], &detection_yaw_cos, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[1 * grid_xy_size + index], &detection_yaw_sin, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[0 * grid_xy_size + index], &detection_vel_x, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[1 * grid_xy_size + index], &detection_vel_y, 1 * sizeof(float),
cudaMemcpyHostToDevice);
auto code = cudaGetLastError();
ASSERT_EQ(cudaSuccess, code);
// Extract the boxes
code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch(
head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(),
head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_);
ASSERT_EQ(cudaSuccess, code);
ASSERT_EQ(1, det_boxes3d.size());
const auto det_box3d = det_boxes3d[0];
EXPECT_EQ(detection_x, det_box3d.x);
EXPECT_EQ(detection_y, det_box3d.y);
EXPECT_EQ(detection_z, det_box3d.z);
EXPECT_NEAR(std::exp(detection_log_w), det_box3d.width, 1e-6);
EXPECT_NEAR(std::exp(detection_log_l), det_box3d.length, 1e-6);
EXPECT_NEAR(std::exp(detection_log_h), det_box3d.height, 1e-6);
EXPECT_EQ(detection_yaw, det_box3d.yaw);
EXPECT_EQ(detection_vel_x, det_box3d.vel_x);
EXPECT_EQ(detection_vel_y, det_box3d.vel_y);
}
TEST_F(PostprocessKernelTest, InvalidYawTest)
{
std::vector<Box3D> det_boxes3d;
constexpr float detection_x = 70.f;
constexpr float detection_y = -38.4f;
constexpr float detection_z = 1.0;
constexpr float detection_yaw_sin = 0.0;
constexpr float detection_yaw_cos = 0.2;
const float idx =
((detection_x - config_ptr_->range_min_x_) /
(config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_));
const float idy =
((detection_y - config_ptr_->range_min_y_) /
(config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_));
const std::size_t index = config_ptr_->down_grid_size_x_ * std::floor(idy) + std::floor(idx);
const float detection_x_offset = idx - std::floor(idx);
const float detection_y_offset = idy - std::floor(idy);
// Set the values in the cuda tensor
const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_;
float score = 1.f;
cudaMemcpy(
&head_out_heatmap_d_[2 * grid_xy_size + index], &score, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[0 * grid_xy_size + index], &detection_x_offset, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[1 * grid_xy_size + index], &detection_y_offset, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_z_d_[0 * grid_xy_size + index], &detection_z, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[0 * grid_xy_size + index], &detection_yaw_cos, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[1 * grid_xy_size + index], &detection_yaw_sin, 1 * sizeof(float),
cudaMemcpyHostToDevice);
auto code = cudaGetLastError();
ASSERT_EQ(cudaSuccess, code);
// Extract the boxes
code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch(
head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(),
head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_);
ASSERT_EQ(cudaSuccess, code);
ASSERT_EQ(0, det_boxes3d.size());
}
TEST_F(PostprocessKernelTest, CircleNMSTest)
{
std::vector<Box3D> det_boxes3d;
constexpr float detection_x = 70.f;
constexpr float detection_y = -38.4f;
constexpr float detection_z = 1.0;
const float detection_log_w = std::log(7.0);
const float detection_log_l = std::log(1.0);
const float detection_log_h = std::log(2.0);
constexpr float detection_yaw1_sin = 0.0;
constexpr float detection_yaw1_cos = 1.0;
constexpr float detection_yaw2_sin = 1.0;
constexpr float detection_yaw2_cos = 0.0;
constexpr float detection_vel_x = 5.0;
constexpr float detection_vel_y = -5.0;
const float idx1 =
((detection_x - config_ptr_->range_min_x_) /
(config_ptr_->voxel_size_x_ * config_ptr_->downsample_factor_));
const float idy1 =
((detection_y - config_ptr_->range_min_y_) /
(config_ptr_->voxel_size_y_ * config_ptr_->downsample_factor_));
const std::size_t index1 = config_ptr_->down_grid_size_x_ * std::floor(idy1) + std::floor(idx1);
const float detection_x_offset1 = idx1 - std::floor(idx1);
const float detection_y_offset1 = idy1 - std::floor(idy1);
const float idx2 = idx1 + 1.0;
const float idy2 = idy1 + 1.0;
const std::size_t index2 = config_ptr_->down_grid_size_x_ * std::floor(idy2) + std::floor(idx2);
const float detection_x_offset2 = detection_x_offset1 - 1.0;
const float detection_y_offset2 = detection_y_offset1 - 1.0;
// Set the values in the cuda tensor
const auto grid_xy_size = config_ptr_->down_grid_size_x_ * config_ptr_->down_grid_size_y_;
float score = 1.f;
cudaMemcpy(
&head_out_heatmap_d_[2 * grid_xy_size + index1], &score, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[0 * grid_xy_size + index1], &detection_x_offset1, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[1 * grid_xy_size + index1], &detection_y_offset1, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_z_d_[0 * grid_xy_size + index1], &detection_z, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[0 * grid_xy_size + index1], &detection_log_w, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[1 * grid_xy_size + index1], &detection_log_l, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[2 * grid_xy_size + index1], &detection_log_h, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[0 * grid_xy_size + index1], &detection_yaw1_cos, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[1 * grid_xy_size + index1], &detection_yaw1_sin, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[0 * grid_xy_size + index1], &detection_vel_x, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[1 * grid_xy_size + index1], &detection_vel_y, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_heatmap_d_[2 * grid_xy_size + index2], &score, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[0 * grid_xy_size + index2], &detection_x_offset2, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_offset_d_[1 * grid_xy_size + index2], &detection_y_offset2, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_z_d_[0 * grid_xy_size + index2], &detection_z, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[0 * grid_xy_size + index2], &detection_log_w, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[1 * grid_xy_size + index2], &detection_log_l, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_dim_d_[2 * grid_xy_size + index2], &detection_log_h, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[0 * grid_xy_size + index2], &detection_yaw2_cos, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_rot_d_[1 * grid_xy_size + index2], &detection_yaw2_sin, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[0 * grid_xy_size + index2], &detection_vel_x, 1 * sizeof(float),
cudaMemcpyHostToDevice);
cudaMemcpy(
&head_out_vel_d_[1 * grid_xy_size + index2], &detection_vel_y, 1 * sizeof(float),
cudaMemcpyHostToDevice);
auto code = cudaGetLastError();
ASSERT_EQ(cudaSuccess, code);
// Extract the boxes
code = postprocess_cuda_ptr_->generateDetectedBoxes3D_launch(
head_out_heatmap_d_.get(), head_out_offset_d_.get(), head_out_z_d_.get(), head_out_dim_d_.get(),
head_out_rot_d_.get(), head_out_vel_d_.get(), det_boxes3d, stream_);
ASSERT_EQ(cudaSuccess, code);
ASSERT_EQ(1, det_boxes3d.size());
}
} // namespace centerpoint
int main(int argc, char ** argv)
{
testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}