From a038a17128a97b4edf6eb7d3840010f68f91c53b Mon Sep 17 00:00:00 2001 From: kminoda Date: Thu, 5 Dec 2024 09:54:37 +0900 Subject: [PATCH 1/3] feat(lidar_centerpoint, pointpainting): move max_voxel_count from _ml_package.param.yaml Signed-off-by: kminoda --- .../config/pointpainting.param.yaml | 1 + .../config/pointpainting_ml_package.param.yaml | 1 - .../src/pointpainting_fusion/node.cpp | 2 +- perception/autoware_lidar_centerpoint/README.md | 2 +- .../autoware_lidar_centerpoint/config/centerpoint.param.yaml | 1 + .../config/centerpoint_ml_package.param.yaml | 1 - .../config/centerpoint_sigma.param.yaml | 1 + .../config/centerpoint_sigma_ml_package.param.yaml | 1 - .../config/centerpoint_tiny.param.yaml | 1 + .../config/centerpoint_tiny_ml_package.param.yaml | 1 - perception/autoware_lidar_centerpoint/src/node.cpp | 2 +- 11 files changed, 7 insertions(+), 7 deletions(-) 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 9227e4fa9319a..7ba9aaadee045 100644 --- a/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml @@ -20,3 +20,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/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 4e0f88e2134ac..6f8c58bc4c332 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 @@ -142,7 +142,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 471712a637dec..896bbb133035e 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 | @@ -62,6 +61,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 53d77e8d1c42c..b284f75669c90 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint.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_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 bd5fc5f3567a5..3b6db28cbd29f 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml @@ -19,3 +19,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 53d77e8d1c42c..b284f75669c90 100644 --- a/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml +++ b/perception/autoware_lidar_centerpoint/config/centerpoint_tiny.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_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/src/node.cpp b/perception/autoware_lidar_centerpoint/src/node.cpp index 5b92e5c811a23..e0712f1636deb 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"); From ad4819a61c0ee2d51051b95fcfd159f9eddc15e7 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Thu, 5 Dec 2024 01:03:18 +0000 Subject: [PATCH 2/3] style(pre-commit): autofix --- perception/autoware_lidar_centerpoint/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/autoware_lidar_centerpoint/README.md b/perception/autoware_lidar_centerpoint/README.md index 896bbb133035e..8ca4180fa256d 100644 --- a/perception/autoware_lidar_centerpoint/README.md +++ b/perception/autoware_lidar_centerpoint/README.md @@ -61,7 +61,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 | +| `max_voxel_size` | int | `40000` | maximum number of voxels | ### The `build_only` option From d2187337435d077ea461cb710f12c3d0d33dfee5 Mon Sep 17 00:00:00 2001 From: kminoda Date: Thu, 5 Dec 2024 11:38:22 +0900 Subject: [PATCH 3/3] update schema Signed-off-by: kminoda --- .../schema/pointpainting.schema.json | 5 +++++ .../schema/pointpainting_ml_package.schema.json | 5 ----- .../schema/centerpoint.schemal.json | 5 +++++ .../schema/centerpoint_ml_package.schema.json | 5 ----- .../schema/centerpoint_tiny_ml_package.schema.json | 5 ----- 5 files changed, 10 insertions(+), 15 deletions(-) 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 57d8bc500f3c6..9e1d02534e01c 100644 --- a/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json +++ b/perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json @@ -94,6 +94,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_lidar_centerpoint/schema/centerpoint.schemal.json b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json index c3268f0e90d9b..d9318d598664b 100644 --- a/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json +++ b/perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json @@ -84,6 +84,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`.",