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;