diff --git a/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml b/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml index 5448dd48dc456..2f5db571c08e0 100644 --- a/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml @@ -19,3 +19,4 @@ omp_params: # omp params num_threads: 1 + max_voxel_size: 40000 diff --git a/perception/autoware_image_projection_based_fusion/config/pointpainting_ml_package.param.yaml b/perception/autoware_image_projection_based_fusion/config/pointpainting_ml_package.param.yaml index ca76a8ecf2dac..43d025b09ef05 100755 --- a/perception/autoware_image_projection_based_fusion/config/pointpainting_ml_package.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/pointpainting_ml_package.param.yaml @@ -4,7 +4,6 @@ class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] voxel_size: [0.32, 0.32, 8.0] downsample_factor: 1 diff --git a/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json b/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json index ab52ac0fcdf2c..023939c957931 100644 --- a/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json @@ -88,6 +88,11 @@ "minimum": 1 } } + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 } }, "required": [] diff --git a/perception/autoware_image_projection_based_fusion/schema/pointpainting_ml_package.schema.json b/perception/autoware_image_projection_based_fusion/schema/pointpainting_ml_package.schema.json index 0f89d050c1828..1215c70de52d4 100644 --- a/perception/autoware_image_projection_based_fusion/schema/pointpainting_ml_package.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/pointpainting_ml_package.schema.json @@ -27,11 +27,6 @@ "description": "A number of channels of point feature layer.", "default": 7 }, - "max_voxel_size": { - "type": "integer", - "description": "A maximum size of voxel grid.", - "default": 40000 - }, "point_cloud_range": { "type": "array", "description": "An array of distance ranges of each class, this must have same length with `class_names`.", diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index bcd62383319c1..dd94c8a0100a2 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -143,7 +143,7 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt const std::size_t point_feature_size = static_cast( this->declare_parameter("model_params.point_feature_size")); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("model_params.max_voxel_size")); + static_cast(this->declare_parameter("max_voxel_size")); pointcloud_range = this->declare_parameter>("model_params.point_cloud_range"); const auto voxel_size = this->declare_parameter>("model_params.voxel_size"); const std::size_t downsample_factor = static_cast( diff --git a/perception/autoware_lidar_centerpoint/README.md b/perception/autoware_lidar_centerpoint/README.md index 06ded16d5fd40..d5b948dd50a40 100644 --- a/perception/autoware_lidar_centerpoint/README.md +++ b/perception/autoware_lidar_centerpoint/README.md @@ -36,7 +36,6 @@ Note that these parameters are associated with ONNX file, predefined during the | -------------------------------------- | ------------ | ------------------------------------------------ | --------------------------------------------------------------------- | | `model_params.class_names` | list[string] | ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] | list of class names for model outputs | | `model_params.point_feature_size` | int | `4` | number of features per point in the point cloud | -| `model_params.max_voxel_size` | int | `40000` | maximum number of voxels | | `model_params.point_cloud_range` | list[double] | [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] | detection range [min_x, min_y, min_z, max_x, max_y, max_z] [m] | | `model_params.voxel_size` | list[double] | [0.32, 0.32, 10.0] | size of each voxel [x, y, z] [m] | | `model_params.downsample_factor` | int | `1` | downsample factor for coordinates | @@ -61,6 +60,7 @@ Note that these parameters are associated with ONNX file, predefined during the | `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. | | `densification_params.world_frame_id` | string | `map` | the world frame id to fuse multi-frame pointcloud | | `densification_params.num_past_frames` | int | `1` | the number of past frames to fuse with the current frame | +| `max_voxel_size` | int | `40000` | maximum number of voxels | ### The `build_only` option diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml index d2f6d3bb3ab6c..9af4077649ec5 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml @@ -17,3 +17,4 @@ densification_params: world_frame_id: map num_past_frames: 1 + max_voxel_size: 40000 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_ml_package.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_ml_package.param.yaml index c8d17890e33be..d33167a7cd161 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_ml_package.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_ml_package.param.yaml @@ -3,7 +3,6 @@ model_params: class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] point_feature_size: 4 - max_voxel_size: 40000 point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] voxel_size: [0.32, 0.32, 10.0] downsample_factor: 1 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml index f4a5d59c3c06f..3f120371fd802 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml @@ -18,3 +18,4 @@ densification_params: world_frame_id: map num_past_frames: 1 + max_voxel_size: 40000 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml index c8d17890e33be..d33167a7cd161 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma_ml_package.param.yaml @@ -3,7 +3,6 @@ model_params: class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] point_feature_size: 4 - max_voxel_size: 40000 point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] voxel_size: [0.32, 0.32, 10.0] downsample_factor: 1 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml index d2f6d3bb3ab6c..9af4077649ec5 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml @@ -17,3 +17,4 @@ densification_params: world_frame_id: map num_past_frames: 1 + max_voxel_size: 40000 diff --git a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml index 2a3f9c8e75290..369181018a125 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny_ml_package.param.yaml @@ -3,7 +3,6 @@ model_params: class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] point_feature_size: 4 - max_voxel_size: 40000 point_cloud_range: [-76.8, -76.8, -4.0, 76.8, 76.8, 6.0] voxel_size: [0.32, 0.32, 10.0] downsample_factor: 2 diff --git a/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json index f2c12b7588f9b..b5ac462973f1f 100644 --- a/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json +++ b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json @@ -78,6 +78,11 @@ "minimum": 0 } } + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 } }, "required": ["post_process_params", "densification_params"] diff --git a/perception/autoware_lidar_centerpoint/schema/centerpoint_ml_package.schema.json b/perception/autoware_lidar_centerpoint/schema/centerpoint_ml_package.schema.json index 2c5655c6201ed..61e7cef24468d 100644 --- a/perception/autoware_lidar_centerpoint/schema/centerpoint_ml_package.schema.json +++ b/perception/autoware_lidar_centerpoint/schema/centerpoint_ml_package.schema.json @@ -21,11 +21,6 @@ "description": "A number of channels of point feature layer.", "default": 4 }, - "max_voxel_size": { - "type": "integer", - "description": "A maximum size of voxel grid.", - "default": 40000 - }, "point_cloud_range": { "type": "array", "description": "An array of distance ranges of each class, this must have same length with `class_names`.", diff --git a/perception/autoware_lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json b/perception/autoware_lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json index 55329e21ea8ab..c9a894a8e3feb 100644 --- a/perception/autoware_lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json +++ b/perception/autoware_lidar_centerpoint/schema/centerpoint_tiny_ml_package.schema.json @@ -21,11 +21,6 @@ "description": "A number of channels of point feature layer.", "default": 4 }, - "max_voxel_size": { - "type": "integer", - "description": "A maximum size of voxel grid.", - "default": 40000 - }, "point_cloud_range": { "type": "array", "description": "An array of distance ranges of each class, this must have same length with `class_names`.", diff --git a/perception/autoware_lidar_centerpoint/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 825fc40234120..dede7499e1705 100644 --- a/perception/autoware_lidar_centerpoint/src/node.cpp +++ b/perception/autoware_lidar_centerpoint/src/node.cpp @@ -62,7 +62,7 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti this->declare_parameter("model_params.point_feature_size")); has_variance_ = this->declare_parameter("model_params.has_variance"); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("model_params.max_voxel_size")); + static_cast(this->declare_parameter("max_voxel_size")); const auto point_cloud_range = this->declare_parameter>("model_params.point_cloud_range"); const auto voxel_size = this->declare_parameter>("model_params.voxel_size");