Skip to content

Commit 9dacd1e

Browse files
authored
chore(autoware_lidar_centerpoint): updated tests (#8158)
chore: updated centerpoin tests. they are currently commented out but they were not compiling (forgot to update them when I added the new cloud capacity parameter) Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp>
1 parent 3e496cc commit 9dacd1e

File tree

3 files changed

+13
-10
lines changed

3 files changed

+13
-10
lines changed

perception/autoware_lidar_centerpoint/test/test_postprocess_kernel.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ void PostprocessKernelTest::SetUp()
2929

3030
constexpr std::size_t class_size{5};
3131
constexpr std::size_t point_feature_size{4};
32+
const std::size_t cloud_capacity{2000000};
3233
constexpr std::size_t max_voxel_size{100000000};
3334
const std::vector<double> point_cloud_range{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0};
3435
const std::vector<double> voxel_size{0.32, 0.32, 10.0};
@@ -40,7 +41,7 @@ void PostprocessKernelTest::SetUp()
4041
constexpr bool has_variance{false};
4142

4243
config_ptr_ = std::make_unique<autoware::lidar_centerpoint::CenterPointConfig>(
43-
class_size, point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
44+
class_size, point_feature_size, cloud_capacity, max_voxel_size, point_cloud_range, voxel_size,
4445
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
4546
yaw_norm_thresholds, has_variance);
4647

perception/autoware_lidar_centerpoint/test/test_voxel_generator.cpp

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@ void VoxelGeneratorTest::SetUp()
3131

3232
class_size_ = 5;
3333
point_feature_size_ = 4;
34+
cloud_capacity_ = 2000000;
3435
max_voxel_size_ = 100000000;
3536
point_cloud_range_ = std::vector<double>{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0};
3637
voxel_size_ = std::vector<double>{0.32, 0.32, 10.0};
@@ -110,9 +111,9 @@ TEST_F(VoxelGeneratorTest, SingleFrame)
110111
autoware::lidar_centerpoint::DensificationParam param(world_frame_, num_past_frames);
111112

112113
autoware::lidar_centerpoint::CenterPointConfig config(
113-
class_size_, point_feature_size_, max_voxel_size_, point_cloud_range_, voxel_size_,
114-
downsample_factor_, encoder_in_feature_size_, score_threshold_, circle_nms_dist_threshold_,
115-
yaw_norm_thresholds_, has_variance_);
114+
class_size_, point_feature_size_, cloud_capacity_, max_voxel_size_, point_cloud_range_,
115+
voxel_size_, downsample_factor_, encoder_in_feature_size_, score_threshold_,
116+
circle_nms_dist_threshold_, yaw_norm_thresholds_, has_variance_);
116117

117118
autoware::lidar_centerpoint::VoxelGenerator voxel_generator(param, config);
118119
std::vector<float> points;
@@ -157,9 +158,9 @@ TEST_F(VoxelGeneratorTest, TwoFramesNoTf)
157158
autoware::lidar_centerpoint::DensificationParam param(world_frame_, num_past_frames);
158159

159160
autoware::lidar_centerpoint::CenterPointConfig config(
160-
class_size_, point_feature_size_, max_voxel_size_, point_cloud_range_, voxel_size_,
161-
downsample_factor_, encoder_in_feature_size_, score_threshold_, circle_nms_dist_threshold_,
162-
yaw_norm_thresholds_, has_variance_);
161+
class_size_, point_feature_size_, cloud_capacity_, max_voxel_size_, point_cloud_range_,
162+
voxel_size_, downsample_factor_, encoder_in_feature_size_, score_threshold_,
163+
circle_nms_dist_threshold_, yaw_norm_thresholds_, has_variance_);
163164

164165
autoware::lidar_centerpoint::VoxelGenerator voxel_generator(param, config);
165166
std::vector<float> points;
@@ -191,9 +192,9 @@ TEST_F(VoxelGeneratorTest, TwoFrames)
191192
autoware::lidar_centerpoint::DensificationParam param(world_frame_, num_past_frames);
192193

193194
autoware::lidar_centerpoint::CenterPointConfig config(
194-
class_size_, point_feature_size_, max_voxel_size_, point_cloud_range_, voxel_size_,
195-
downsample_factor_, encoder_in_feature_size_, score_threshold_, circle_nms_dist_threshold_,
196-
yaw_norm_thresholds_, has_variance_);
195+
class_size_, point_feature_size_, cloud_capacity_, max_voxel_size_, point_cloud_range_,
196+
voxel_size_, downsample_factor_, encoder_in_feature_size_, score_threshold_,
197+
circle_nms_dist_threshold_, yaw_norm_thresholds_, has_variance_);
197198

198199
autoware::lidar_centerpoint::VoxelGenerator voxel_generator(param, config);
199200
std::vector<float> points;

perception/autoware_lidar_centerpoint/test/test_voxel_generator.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,7 @@ class VoxelGeneratorTest : public testing::Test
5151

5252
std::size_t class_size_{};
5353
float point_feature_size_{};
54+
std::size_t cloud_capacity_{};
5455
std::size_t max_voxel_size_{};
5556

5657
std::vector<double> point_cloud_range_{};

0 commit comments

Comments
 (0)