diff --git a/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp b/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp index 85c408b93f4ca..bc30ca04ebfe6 100644 --- a/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp +++ b/perception/autoware_lidar_transfusion/test/test_postprocess_kernel.cpp @@ -26,15 +26,17 @@ void PostprocessKernelTest::SetUp() { cudaStreamCreate(&stream_); + auto cloud_capacity = 2000000; auto voxels_num = std::vector{1, 3, 5}; auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; auto voxel_size = std::vector{0.3, 0.3, 8.0}; + auto num_proposals = 500; auto score_threshold = 0.2f; auto circle_nms_dist_threshold = 0.5f; auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; config_ptr_ = std::make_unique( - voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, - score_threshold); + cloud_capacity, voxels_num, point_cloud_range, voxel_size, num_proposals, + circle_nms_dist_threshold, yaw_norm_thresholds, score_threshold); post_ptr_ = std::make_unique(*config_ptr_, stream_); cls_size_ = config_ptr_->num_proposals_ * config_ptr_->num_classes_; diff --git a/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp b/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp index 1dbbf27d4a127..c4a1c37b4ff77 100644 --- a/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp +++ b/perception/autoware_lidar_transfusion/test/test_preprocess_kernel.cpp @@ -32,15 +32,17 @@ void PreprocessKernelTest::SetUp() { cudaStreamCreate(&stream_); + auto cloud_capacity = 2000000; auto voxels_num = std::vector{1, 3, 5}; auto point_cloud_range = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; auto voxel_size = std::vector{0.3, 0.3, 8.0}; + auto num_proposals = 500; auto score_threshold = 0.2f; auto circle_nms_dist_threshold = 0.5f; auto yaw_norm_thresholds = std::vector{0.5, 0.5, 0.5}; config_ptr_ = std::make_unique( - voxels_num, point_cloud_range, voxel_size, circle_nms_dist_threshold, yaw_norm_thresholds, - score_threshold); + cloud_capacity, voxels_num, point_cloud_range, voxel_size, num_proposals, + circle_nms_dist_threshold, yaw_norm_thresholds, score_threshold); pre_ptr_ = std::make_unique(*config_ptr_, stream_); voxel_features_size_ = config_ptr_->max_voxels_ * config_ptr_->max_num_points_per_pillar_ * diff --git a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp index d8d7db1302761..5a60c206314bf 100644 --- a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp +++ b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp @@ -35,15 +35,17 @@ void VoxelGeneratorTest::SetUp() delta_pointcloud_x_ = 1.0; points_per_pointcloud_ = 300; + cloud_capacity_ = 2000000; voxels_num_ = std::vector{5000, 30000, 60000}; point_cloud_range_ = std::vector{-76.8, -76.8, -3.0, 76.8, 76.8, 5.0}; voxel_size_ = std::vector{0.3, 0.3, 8.0}; + num_proposals_ = 500; score_threshold_ = 0.2f; circle_nms_dist_threshold_ = 0.5f; yaw_norm_thresholds_ = std::vector{0.5, 0.5, 0.5}; config_ptr_ = std::make_unique( - voxels_num_, point_cloud_range_, voxel_size_, circle_nms_dist_threshold_, yaw_norm_thresholds_, - score_threshold_); + cloud_capacity_, voxels_num_, point_cloud_range_, voxel_size_, num_proposals_, + circle_nms_dist_threshold_, yaw_norm_thresholds_, score_threshold_); cloud1_ = std::make_unique(); cloud2_ = std::make_unique(); diff --git a/perception/autoware_lidar_transfusion/test/test_voxel_generator.hpp b/perception/autoware_lidar_transfusion/test/test_voxel_generator.hpp index 641a42322a302..49346e69054f3 100644 --- a/perception/autoware_lidar_transfusion/test/test_voxel_generator.hpp +++ b/perception/autoware_lidar_transfusion/test/test_voxel_generator.hpp @@ -51,9 +51,11 @@ class VoxelGeneratorTest : public testing::Test double delta_pointcloud_x_{}; std::size_t points_per_pointcloud_{}; + std::size_t cloud_capacity_{}; std::vector voxels_num_{}; std::vector point_cloud_range_{}; std::vector voxel_size_{}; + std::size_t num_proposals_{}; float circle_nms_dist_threshold_{}; std::vector yaw_norm_thresholds_{}; float score_threshold_{};