Skip to content

Commit

Permalink
chore(autoware_lidar_centerpoint): updated tests (autowarefoundation#…
Browse files Browse the repository at this point in the history
…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 <[email protected]>
  • Loading branch information
knzo25 authored and a-maumau committed Jul 28, 2024
1 parent f784592 commit 47eb31e
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ void PostprocessKernelTest::SetUp()

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};
Expand All @@ -40,7 +41,7 @@ void PostprocessKernelTest::SetUp()
constexpr bool has_variance{false};

config_ptr_ = std::make_unique<autoware::lidar_centerpoint::CenterPointConfig>(
class_size, point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ void VoxelGeneratorTest::SetUp()

class_size_ = 5;
point_feature_size_ = 4;
cloud_capacity_ = 2000000;
max_voxel_size_ = 100000000;
point_cloud_range_ = std::vector<double>{-76.8, -76.8, -4.0, 76.8, 76.8, 6.0};
voxel_size_ = std::vector<double>{0.32, 0.32, 10.0};
Expand Down Expand Up @@ -110,9 +111,9 @@ TEST_F(VoxelGeneratorTest, SingleFrame)
autoware::lidar_centerpoint::DensificationParam param(world_frame_, num_past_frames);

autoware::lidar_centerpoint::CenterPointConfig config(
class_size_, point_feature_size_, 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_);
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_);

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

autoware::lidar_centerpoint::CenterPointConfig config(
class_size_, point_feature_size_, 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_);
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_);

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

autoware::lidar_centerpoint::CenterPointConfig config(
class_size_, point_feature_size_, 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_);
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_);

autoware::lidar_centerpoint::VoxelGenerator voxel_generator(param, config);
std::vector<float> points;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ class VoxelGeneratorTest : public testing::Test

std::size_t class_size_{};
float point_feature_size_{};
std::size_t cloud_capacity_{};
std::size_t max_voxel_size_{};

std::vector<double> point_cloud_range_{};
Expand Down

0 comments on commit 47eb31e

Please sign in to comment.