From 837a3297703143589bf2496b3379f0747c5b27dd Mon Sep 17 00:00:00 2001 From: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Date: Mon, 17 Feb 2025 15:16:54 +0900 Subject: [PATCH] fix(autoware_pointcloud_preprocessor): empty input validation (#10115) * fix(autoware_pointcloud_preprocessor): fix 0 division Signed-off-by: Shumpei Wakabayashi * style(pre-commit): autofix * fix float and error throttle Signed-off-by: Shumpei Wakabayashi * style(pre-commit): autofix * fix Signed-off-by: Shumpei Wakabayashi * fix param validation Signed-off-by: Shumpei Wakabayashi * fix unused var Signed-off-by: Shumpei Wakabayashi * feat add input validatoin Signed-off-by: Shumpei Wakabayashi * fix too cautious floating Signed-off-by: Shumpei Wakabayashi * fix error msg Signed-off-by: Shumpei Wakabayashi * fix plural Signed-off-by: Shumpei Wakabayashi * fix: set exclusiveMinimum 0.0 Signed-off-by: Shumpei Wakabayashi * fix: reomve unnecessary validatoin Signed-off-by: Shumpei Wakabayashi --------- Signed-off-by: Shumpei Wakabayashi Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- ...ckup_based_voxel_grid_downsample_filter_node.schema.json | 6 +++--- .../pickup_based_voxel_grid_downsample_filter_node.cpp | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter_node.schema.json b/sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter_node.schema.json index 2e3b7f41787c8..320b9d30c9dd5 100644 --- a/sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter_node.schema.json +++ b/sensing/autoware_pointcloud_preprocessor/schema/pickup_based_voxel_grid_downsample_filter_node.schema.json @@ -10,19 +10,19 @@ "type": "number", "description": "voxel size along the x-axis [m]", "default": "1.0", - "minimum": 0 + "exclusiveMinimum": 0.0 }, "voxel_size_y": { "type": "number", "description": "voxel size along the y-axis [m]", "default": "1.0", - "minimum": 0 + "exclusiveMinimum": 0.0 }, "voxel_size_z": { "type": "number", "description": "voxel size along the z-axis [m]", "default": "1.0", - "minimum": 0 + "exclusiveMinimum": 0.0 } }, "required": ["voxel_size_x", "voxel_size_y", "voxel_size_z"], diff --git a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp index 0c467234d6591..996a7f8206728 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp @@ -90,6 +90,7 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter( // std::unordered_map voxel_map; robin_hood::unordered_map voxel_map; + if (input->data.empty()) return; voxel_map.reserve(input->data.size() / input->point_step); constexpr float large_num_offset = 100000.0;