diff --git a/launch/tier4_localization_launch/package.xml b/launch/tier4_localization_launch/package.xml index 5a79e29858725..cad24a0498925 100644 --- a/launch/tier4_localization_launch/package.xml +++ b/launch/tier4_localization_launch/package.xml @@ -23,11 +23,15 @@ autoware_geo_pose_projector autoware_gyro_odometer autoware_lidar_marker_localizer + autoware_localization_error_monitor autoware_ndt_scan_matcher autoware_pointcloud_preprocessor + autoware_pose_covariance_modifier autoware_pose_estimator_arbiter autoware_pose_initializer autoware_pose_instability_detector + autoware_stop_filter + autoware_twist2accel eagleye_geo_pose_fusion eagleye_gnss_converter eagleye_rt 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;