From 9bb04cee8803d5f8479ae58197c21931c75b5613 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Wed, 14 Jan 2026 16:08:31 +0900 Subject: [PATCH 01/15] Update docker installation commit for perception_evaluation --- Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index c5240c498..22d18f5ba 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,7 +61,7 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@develop +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@dd37a546352f953565033f1d4b8cb443df1232c59 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ From 3af4270f9259f2ba16e422a83f701d3064c04706 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Fri, 29 May 2026 19:10:37 +0900 Subject: [PATCH 02/15] Updated --- .../datasets/transforms/__init__.py | 3 +- .../datasets/transforms/local_3d_bbox.py | 77 +++++++++++++++++++ ..._voxel_second_secfpn_50e_8xb8_base_120m.py | 2 +- .../default/pipelines/default_lidar_120m.py | 20 ++++- .../pipelines/default_lidar_intensity_120m.py | 18 +++++ 5 files changed, 117 insertions(+), 3 deletions(-) create mode 100644 autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py diff --git a/autoware_ml/detection3d/datasets/transforms/__init__.py b/autoware_ml/detection3d/datasets/transforms/__init__.py index 6bc932f1a..b20961db6 100644 --- a/autoware_ml/detection3d/datasets/transforms/__init__.py +++ b/autoware_ml/detection3d/datasets/transforms/__init__.py @@ -1,3 +1,4 @@ from .object_min_points_filter import ObjectMinPointsFilter +from .local_3d_bbox import Local3DBBoxExpand -__all__ = ["ObjectMinPointsFilter"] +__all__ = ["ObjectMinPointsFilter", "Local3DBBoxExpand"] diff --git a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py new file mode 100644 index 000000000..5f61db235 --- /dev/null +++ b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py @@ -0,0 +1,77 @@ +from typing import List + +import numpy as np + +from mmcv.transforms import BaseTransform +from mmdet3d.structures.ops import box_np_ops +from mmengine.registry import TRANSFORMS + + +@TRANSFORMS.register_module() +class Local3DBBoxExpand(BaseTransform): + """Locally expand the 3D bounding boxes by scaling the width, which it doesn't scale the points. + + Args: + expand_widths: (List[float]): Uniformly sampled expand width. + width_dim: (int): The dimension of the width. Default is 4, which is the width dimension of the 3D + bounding box. Since 3D Bbox is in the format of [x, y, z, dx, dy, dz, heading], the width dimension is the + 4th dimension. + label_ids: (List[int]): The label IDs to expand. If None, all label IDs will be expanded. + """ + + def __init__( + self, + expand_widths: List[float], + expand_lengths: Optional[List[float]] = None, + length_dim: int = 3, + width_dim: int = 4, + label_ids: List[int] = None) -> None: + + super().__init__() + assert isinstance(expand_widths, list) + assert len(expand_widths) == 2 + assert expand_widths[0] < expand_widths[1] + if expand_lengths is not None: + assert isinstance(expand_lengths, list) + assert len(expand_lengths) == 2 + assert expand_lengths[0] < expand_lengths[1] + self.expand_lengths = expand_lengths + self.length_dim = length_dim + self.expand_widths = expand_widths + self.width_dim = width_dim + self.label_ids = label_ids + + def transform(self, input_dict: dict) -> dict: + """Call function to locally augment the 3D bounding boxes by scaling the width. + + Args: + input_dict (dict): Result dict from loading pipeline. + + Returns: + dict: Results after locally augmenting the 3D bounding boxes by scaling the width, 'gt_bboxes_3d' \ + key is updated in the result dict. + """ + # Label mask + if self.label_ids is not None: + label_masks = [True if label in self.label_ids else False for label in input_dict["gt_labels_3d"]] + else: + label_masks = np.ones(len(input_dict["gt_labels_3d"]), dtype=bool) + + for i in range(len(input_dict["gt_bboxes_3d"])): + if not label_masks[i]: + continue + + expand_width = np.random.uniform(self.expand_widths[0], self.expand_widths[1]) + input_dict["gt_bboxes_3d"].tensor[i, self.width_dim] += expand_width + if self.expand_lengths is not None: + expand_length = np.random.uniform(self.expand_lengths[0], self.expand_lengths[1]) + input_dict["gt_bboxes_3d"].tensor[i, self.length_dim] += expand_length + + return input_dict + + def __repr__(self) -> str: + """str: Return a string that describes the module.""" + repr_str = self.__class__.__name__ + repr_str += f"(expand_widths={self.expand_widths}, expand_lengths={self.expand_lengths}, \ + length_dim={self.length_dim}, width_dim={self.width_dim}, label_ids={self.label_ids})" + return repr_str \ No newline at end of file diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py index 79337d976..44b924893 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py @@ -13,7 +13,7 @@ # user setting data_root = "data/t4dataset/" -info_directory_path = "info/user_name/" +info_directory_path = "info/kokseang_2_7/" experiment_group_name = "bevfusion_lidar/base/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_50e_8xb8_base_120m" diff --git a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py index 06d95be16..3032ac825 100644 --- a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py +++ b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py @@ -40,6 +40,24 @@ test_mode=False, ), dict(type="LoadAnnotations3D", with_bbox_3d=True, with_label_3d=True, with_attr_label=False), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.20, 0.40], # 10cm - 20cm to each side + label_ids=[0], # car + expand_lengths=None, # no expand + ), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.50, 0.80], # 25cm - 40cm to each side + label_ids=[1], # trucks + expand_lengths=[0.4, 0.60], # 20cm - 30cm to each side + ), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.5, 0.8], # 25cm - 40cm to each side + label_ids=[2], # buses + expand_lengths=[0.5, 0.9], # 25cm - 45cm to each side + ), dict( type="BEVFusionGlobalRotScaleTrans", scale_ratio_range=[0.95, 1.05], @@ -47,7 +65,7 @@ translation_std=[0.5, 0.5, 0.2], ), dict(type="BEVFusionRandomFlip3D"), - dict(type="PointsRangeFilter", point_cloud_range=point_cloud_range), + dict(type="PointsRangeFilter", point_cloud_range=point_cloud_range), dict(type="ObjectRangeFilter", point_cloud_range=point_cloud_range), dict( type="ObjectNameFilter", diff --git a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py index 4e74d3616..4f753174c 100644 --- a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py +++ b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py @@ -40,6 +40,24 @@ test_mode=False, ), dict(type="LoadAnnotations3D", with_bbox_3d=True, with_label_3d=True, with_attr_label=False), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.20, 0.40], # 10cm - 20cm to each side + label_ids=[0], # car + expand_lengths=None, # no expand + ), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.50, 0.80], # 25cm - 40cm to each side + label_ids=[1], # trucks + expand_lengths=[0.4, 0.60], # 20cm - 30cm to each side + ), + dict( + type='Local3DBBoxExpand', + expand_widths=[0.5, 0.8], # 25cm - 40cm to each side + label_ids=[2], # buses + expand_lengths=[0.5, 0.9], # 25cm - 45cm to each side + ), dict( type="BEVFusionGlobalRotScaleTrans", scale_ratio_range=[0.95, 1.05], From ee41b59a0f874c4c703e56a7fe6a084d985d1a00 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Sat, 30 May 2026 00:53:30 +0900 Subject: [PATCH 03/15] Updated --- .../datasets/transforms/local_3d_bbox.py | 32 +++++++++---------- ...second_secfpn_30e_8xb8_j6gen2_base_120m.py | 6 ++-- 2 files changed, 19 insertions(+), 19 deletions(-) diff --git a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py index 5f61db235..b5ab84293 100644 --- a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py +++ b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py @@ -1,4 +1,4 @@ -from typing import List +from typing import List, Optional import numpy as np @@ -20,21 +20,21 @@ class Local3DBBoxExpand(BaseTransform): """ def __init__( - self, - expand_widths: List[float], - expand_lengths: Optional[List[float]] = None, - length_dim: int = 3, - width_dim: int = 4, - label_ids: List[int] = None) -> None: - - super().__init__() + self, + expand_widths: List[float], + expand_lengths: Optional[List[float]] = None, + length_dim: int = 3, + width_dim: int = 4, + label_ids: List[int] = None) -> None: + + super().__init__() assert isinstance(expand_widths, list) assert len(expand_widths) == 2 assert expand_widths[0] < expand_widths[1] if expand_lengths is not None: assert isinstance(expand_lengths, list) - assert len(expand_lengths) == 2 - assert expand_lengths[0] < expand_lengths[1] + assert len(expand_lengths) == 2 + assert expand_lengths[0] < expand_lengths[1] self.expand_lengths = expand_lengths self.length_dim = length_dim self.expand_widths = expand_widths @@ -63,15 +63,15 @@ def transform(self, input_dict: dict) -> dict: expand_width = np.random.uniform(self.expand_widths[0], self.expand_widths[1]) input_dict["gt_bboxes_3d"].tensor[i, self.width_dim] += expand_width - if self.expand_lengths is not None: - expand_length = np.random.uniform(self.expand_lengths[0], self.expand_lengths[1]) - input_dict["gt_bboxes_3d"].tensor[i, self.length_dim] += expand_length + if self.expand_lengths is not None: + expand_length = np.random.uniform(self.expand_lengths[0], self.expand_lengths[1]) + input_dict["gt_bboxes_3d"].tensor[i, self.length_dim] += expand_length - return input_dict + return input_dict def __repr__(self) -> str: """str: Return a string that describes the module.""" repr_str = self.__class__.__name__ repr_str += f"(expand_widths={self.expand_widths}, expand_lengths={self.expand_lengths}, \ - length_dim={self.length_dim}, width_dim={self.width_dim}, label_ids={self.label_ids})" + length_dim={self.length_dim}, width_dim={self.width_dim}, label_ids={self.label_ids})" return repr_str \ No newline at end of file diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py index 9da67036e..773438c94 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py @@ -13,9 +13,9 @@ # user setting data_root = "data/t4dataset/" -info_directory_path = "info/user_name/" +info_directory_path = "info/kokseang_2_8/" -experiment_group_name = "bevfusion_lidar_intensity/j6gen2_base/" + _base_.dataset_type +experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name @@ -160,4 +160,4 @@ ) log_processor = dict(window_size=50) -load_from = None +load_from = "work_dirs/bevfusion_lidar_2.7.0/base/epoch_48.pth" From 7ae4bd50c341168eb3110734f8cbc7975a983247 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Sat, 30 May 2026 11:50:51 +0900 Subject: [PATCH 04/15] Updated --- tools/detection3d/t4dataset_converters/t4converter.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/tools/detection3d/t4dataset_converters/t4converter.py b/tools/detection3d/t4dataset_converters/t4converter.py index 842b0f458..123489b4f 100644 --- a/tools/detection3d/t4dataset_converters/t4converter.py +++ b/tools/detection3d/t4dataset_converters/t4converter.py @@ -628,6 +628,10 @@ def get_lidarseg_annotations( return dict() assert i < len(t4.lidarseg), "Index exceeds number of lidarseg records!" + if sd_record.info_filename is None: + print(f"sample {lidar_token} doesn't have lidar info_filename") + return dict() + assert t4.lidarseg[i].sample_data_token == lidar_token, "Sample data token mismatch!" return dict( pts_semantic_mask_path=parse_lidar_path(osp.join(t4.data_root, t4.lidarseg[i].filename)), From b4f0b63dee059ac86d1b51a2f09c9b8ca1ff916e Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Sat, 30 May 2026 18:45:35 +0900 Subject: [PATCH 05/15] Updated --- ...usion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py index 773438c94..d9bfb144d 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py @@ -13,7 +13,7 @@ # user setting data_root = "data/t4dataset/" -info_directory_path = "info/kokseang_2_8/" +info_directory_path = "info/kokseang_2_7/" experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m" From fdacd08a8195dc7fa86a4061c839652def3f0fda Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Mon, 1 Jun 2026 17:49:41 +0900 Subject: [PATCH 06/15] Updated --- Dockerfile | 6 ++++-- .../configs/detection3d/dataset/t4dataset/j6gen2_base.py | 4 ++-- .../detection3d/datasets/transforms/local_3d_bbox.py | 4 ++-- ...n_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py | 2 +- tools/detection3d/test.py | 2 +- 5 files changed, 10 insertions(+), 8 deletions(-) diff --git a/Dockerfile b/Dockerfile index 3e9caecb9..fe58c44c9 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,13 +61,15 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@9d8c9773d35177bb0b7f2606f429f58a5fb708ca +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@95520e79f0ce5c02de414605617c7853e7a83731 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ setuptools==60.2.0 \ transformers==4.51.3 \ - polars==1.37.1 + polars==1.37.1 \ + onnx_graphsurgeon==0.5.8 \ + spconv-cu126==2.3.8 # NOTE(knzo25): this patch is needed to use numpy versions over 1.23.5 (version used in mmdet3d 1.4.0) # It can be safely deleted when mmdet3d updates the numpy version diff --git a/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py b/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py index cc3a86d3e..a9ba007d8 100644 --- a/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py +++ b/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py @@ -34,8 +34,8 @@ dataset_test_groups = { "largebus": ("t4dataset_largebus_infos_test.pkl", False), - "j6gen2": ("t4dataset_j6gen2_infos_test.pkl", False), - "j6gen2_base": ("t4dataset_j6gen2_base_infos_test.pkl", True), + # "j6gen2": ("t4dataset_j6gen2_infos_test.pkl", False), + # "j6gen2_base": ("t4dataset_j6gen2_base_infos_test.pkl", True), } # dataset format setting diff --git a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py index b5ab84293..f35c8e7c0 100644 --- a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py +++ b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py @@ -60,14 +60,14 @@ def transform(self, input_dict: dict) -> dict: for i in range(len(input_dict["gt_bboxes_3d"])): if not label_masks[i]: continue - + expand_width = np.random.uniform(self.expand_widths[0], self.expand_widths[1]) input_dict["gt_bboxes_3d"].tensor[i, self.width_dim] += expand_width if self.expand_lengths is not None: expand_length = np.random.uniform(self.expand_lengths[0], self.expand_lengths[1]) input_dict["gt_bboxes_3d"].tensor[i, self.length_dim] += expand_length - return input_dict + return input_dict def __repr__(self) -> str: """str: Return a string that describes the module.""" diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py index d9bfb144d..120e9bc40 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py @@ -15,7 +15,7 @@ data_root = "data/t4dataset/" info_directory_path = "info/kokseang_2_7/" -experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand/" + _base_.dataset_type +experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand_adjusted_test/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name diff --git a/tools/detection3d/test.py b/tools/detection3d/test.py index 64489fbaa..0f609ed5a 100644 --- a/tools/detection3d/test.py +++ b/tools/detection3d/test.py @@ -129,7 +129,7 @@ def main(): dataset_file, evaluate_frame_prefix = dataset_configs cfg.test_dataloader.dataset.ann_file = osp.join(cfg.info_directory_path, dataset_file) cfg.test_evaluator.dataset_name = dataset_name - cfg.test_evaluator.evaluate_frame_prefix = evaluate_frame_prefix + # cfg.test_evaluator.evaluate_frame_prefix = evaluate_frame_prefix cfg.test_evaluator.ann_file = osp.join(cfg.data_root, cfg.info_directory_path, dataset_file) # build the runner from config From a6903eb8d649f46717c66acede5a75ffc06088fb Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Tue, 2 Jun 2026 19:27:58 +0900 Subject: [PATCH 07/15] Updated --- Dockerfile | 2 +- .../evaluation/t4metric/t4metric_v2.py | 60 ++++++++++++++++++- 2 files changed, 59 insertions(+), 3 deletions(-) diff --git a/Dockerfile b/Dockerfile index fe58c44c9..7ef0d8d13 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,7 +61,7 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@95520e79f0ce5c02de414605617c7853e7a83731 +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@f67600293e3e74861f913da3efafd6bf436d2ab6 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ diff --git a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py index c7865320f..dde3971cd 100644 --- a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py +++ b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py @@ -985,11 +985,27 @@ def _aggregate_metrics_data( # Create precision_interpolate and recall_interpolate keys iterable_metrics[ - f"T4MetricV2_label_detection/{label_name}_precisions_{matching_mode}_{threshold}" + f"T4MetricV2_label_detection/{label_name}_interp-precisions_{matching_mode}_{threshold}" ] = ap.precision_interp.tolist() iterable_metrics[ - f"T4MetricV2_label_detection/{label_name}_recalls_{matching_mode}_{threshold}" + f"T4MetricV2_label_detection/{label_name}_interp-recalls_{matching_mode}_{threshold}" ] = ap.recall_interp.tolist() + iterable_metrics[ + f"T4MetricV2_label_detection/{label_name}_interp-confs_{matching_mode}_{threshold}" + ] = ap.conf_interp.tolist() + + # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) + if ap.tp_error_metrics is not None: + for tp_error_metric in ap.tp_error_metrics: + mode = tp_error_metric.mode + average_mode = tp_error_metric.average_mode + + metric_dict[ + f"T4MetricV2_label_detection/{label_name}_{mode}_values_{matching_mode}_{threshold}" + ] = tp_error_metric.values.tolist() + metric_dict[ + f"T4MetricV2_label_detection/{label_name}_{mode}_interp-values_{matching_mode}_{threshold}" + ] = tp_error_metric.interpolated_values.tolist() return iterable_metrics @@ -1044,6 +1060,31 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato ap.optimal_precision ) + # Number of prediction matches (TPs) and matches at the optimal confidence threshold + metric_dict[f"T4MetricV2_label/{label_name}_num-match_{matching_mode}_{threshold}"] = ap.num_tp + metric_dict[ + f"T4MetricV2_label/{label_name}_optimal-num-match_{matching_mode}_{threshold}" + ] = ap.num_tp_at_optimal_conf + + # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) + if ap.tp_error_metrics is not None: + for tp_error_metric in ap.tp_error_metrics: + mode = tp_error_metric.mode + average_mode = tp_error_metric.average_mode + + metric_dict[ + f"T4MetricV2_label/{label_name}_{mode}_values_{matching_mode}_{threshold}" + ] = tp_error_metric.values.tolist() + metric_dict[ + f"T4MetricV2_label/{label_name}_{mode}_interpolated-values_{matching_mode}_{threshold}" + ] = tp_error_metric.interpolated_values.tolist() + metric_dict[ + f"T4MetricV2_label/{label_name}_{average_mode}_{matching_mode}_{threshold}" + ] = tp_error_metric.avg_metric + metric_dict[ + f"T4MetricV2_label/{label_name}_optimal-{average_mode}_{matching_mode}_{threshold}" + ] = tp_error_metric.optimal_avg_metric + # Label metadata key metric_dict[f"metadata_label/test_{label_name}_num_predictions"] = label_num_preds metric_dict[f"metadata_label/test_{label_name}_num_ground_truths"] = label_num_gts @@ -1054,6 +1095,21 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato metric_dict[map_key] = map_instance.map metric_dict[maph_key] = map_instance.maph + # Add mean TP errors (e.g. mATE, mAOE, mASE, mAVE, mAAE) + if map_instance.mean_tp_errors is not None: + for mean_tp_error_name, mean_tp_error_value in map_instance.mean_tp_errors.items(): + metric_dict[f"T4MetricV2/{mean_tp_error_name}_{matching_mode}"] = mean_tp_error_value + + # Add NuScenes Detection Score (NDS) based on mAP and mAPH + if map_instance.map_based_nds is not None: + metric_dict[ + f"T4MetricV2/{map_instance.map_based_nds.metric_prefix_name}_nds_{matching_mode}" + ] = map_instance.map_based_nds.nds + if map_instance.mapH_based_nds is not None: + metric_dict[ + f"T4MetricV2/{map_instance.mapH_based_nds.metric_prefix_name}_nds_{matching_mode}" + ] = map_instance.mapH_based_nds.nds + total_num_preds = num_preds # Selected evaluator From 90e572ca8b6cd9a7aa4f54051a576e72033ff2c7 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Wed, 3 Jun 2026 10:44:45 +0900 Subject: [PATCH 08/15] Updated --- Dockerfile | 2 +- .../evaluation/t4metric/t4metric_v2.py | 50 +++++++++++++------ 2 files changed, 37 insertions(+), 15 deletions(-) diff --git a/Dockerfile b/Dockerfile index 7ef0d8d13..8867b972a 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,7 +61,7 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@f67600293e3e74861f913da3efafd6bf436d2ab6 +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@076a6c7e98383f1e13df49fb3b83bc1d10124526 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ diff --git a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py index dde3971cd..c62af88a8 100644 --- a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py +++ b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py @@ -994,16 +994,16 @@ def _aggregate_metrics_data( f"T4MetricV2_label_detection/{label_name}_interp-confs_{matching_mode}_{threshold}" ] = ap.conf_interp.tolist() - # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) + # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) if ap.tp_error_metrics is not None: for tp_error_metric in ap.tp_error_metrics: mode = tp_error_metric.mode average_mode = tp_error_metric.average_mode - metric_dict[ + iterable_metrics[ f"T4MetricV2_label_detection/{label_name}_{mode}_values_{matching_mode}_{threshold}" ] = tp_error_metric.values.tolist() - metric_dict[ + iterable_metrics[ f"T4MetricV2_label_detection/{label_name}_{mode}_interp-values_{matching_mode}_{threshold}" ] = tp_error_metric.interpolated_values.tolist() @@ -1073,17 +1073,20 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato average_mode = tp_error_metric.average_mode metric_dict[ - f"T4MetricV2_label/{label_name}_{mode}_values_{matching_mode}_{threshold}" - ] = tp_error_metric.values.tolist() - metric_dict[ - f"T4MetricV2_label/{label_name}_{mode}_interpolated-values_{matching_mode}_{threshold}" - ] = tp_error_metric.interpolated_values.tolist() - metric_dict[ - f"T4MetricV2_label/{label_name}_{average_mode}_{matching_mode}_{threshold}" + f"T4MetricV2_label/{label_name}_tp-error_{average_mode}_{matching_mode}_{threshold}" ] = tp_error_metric.avg_metric metric_dict[ - f"T4MetricV2_label/{label_name}_optimal-{average_mode}_{matching_mode}_{threshold}" + f"T4MetricV2_label/{label_name}_tp-error-min-recall-conf_{average_mode}_{matching_mode}_{threshold}" + ] = tp_error_metric.min_recall_conf + metric_dict[ + f"T4MetricV2_label/{label_name}_tp-error-optimal-{average_mode}_{matching_mode}_{threshold}" ] = tp_error_metric.optimal_avg_metric + metric_dict[ + f"T4MetricV2_label/{label_name}_tp-error-medium-{average_mode}_{matching_mode}_{threshold}" + ] = tp_error_metric.medium_avg_metric + metric_dict[ + f"T4MetricV2_label/{label_name}_tp-error-medium-recall-conf-{average_mode}_{matching_mode}_{threshold}" + ] = tp_error_metric.medium_recall_conf # Label metadata key metric_dict[f"metadata_label/test_{label_name}_num_predictions"] = label_num_preds @@ -1098,17 +1101,33 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato # Add mean TP errors (e.g. mATE, mAOE, mASE, mAVE, mAAE) if map_instance.mean_tp_errors is not None: for mean_tp_error_name, mean_tp_error_value in map_instance.mean_tp_errors.items(): - metric_dict[f"T4MetricV2/{mean_tp_error_name}_{matching_mode}"] = mean_tp_error_value - + metric_dict[f"T4MetricV2/mean-tp-error_{mean_tp_error_name}_{matching_mode}"] = mean_tp_error_value + + optimal_mean_tp_errors = map_instance.optimal_mean_tp_errors.get(mean_tp_error_name, None) + if optimal_mean_tp_errors is not None: + metric_dict[f"T4MetricV2/mean-tp-error-optimal-{mean_tp_error_name}_{matching_mode}"] = optimal_mean_tp_errors + + medium_mean_tp_errors = map_instance.medium_mean_tp_errors.get(mean_tp_error_name, None) + if medium_mean_tp_errors is not None: + metric_dict[f"T4MetricV2/mean-tp-error-medium-{mean_tp_error_name}_{matching_mode}"] = medium_mean_tp_errors + # Add NuScenes Detection Score (NDS) based on mAP and mAPH if map_instance.map_based_nds is not None: metric_dict[ f"T4MetricV2/{map_instance.map_based_nds.metric_prefix_name}_nds_{matching_mode}" ] = map_instance.map_based_nds.nds + if map_instance.medium_map_based_nds is not None: + metric_dict[ + f"T4MetricV2/{map_instance.medium_map_based_nds.metric_prefix_name}_nds_{matching_mode}" + ] = map_instance.medium_map_based_nds.nds if map_instance.mapH_based_nds is not None: metric_dict[ f"T4MetricV2/{map_instance.mapH_based_nds.metric_prefix_name}_nds_{matching_mode}" ] = map_instance.mapH_based_nds.nds + if map_instance.medium_mapH_based_nds is not None: + metric_dict[ + f"T4MetricV2/{map_instance.medium_mapH_based_nds.metric_prefix_name}_nds_{matching_mode}" + ] = map_instance.medium_mapH_based_nds.nds total_num_preds = num_preds @@ -1165,7 +1184,10 @@ def _write_aggregated_metrics( aggregated_metrics[evaluator_name]["metadata_label"][label_name] = {} aggregated_metrics[evaluator_name]["metadata_label"][label_name][key] = value - elif key.startswith("T4MetricV2/mAP_") or key.startswith("T4MetricV2/mAPH_"): + elif key.startswith("T4MetricV2/tp-mean-error"): + # These are TP error metrics, put them in the metrics section + aggregated_metrics[evaluator_name]["tp_mean_errors"][key] = value + elif key.startswith("T4MetricV2/mAP_") or key.startswith("T4MetricV2/mAPH_") or "nds" in key: # These are overall metrics, put them in the metrics section aggregated_metrics[evaluator_name]["metrics"][key] = value else: From 309cd5c5774b61e44d6745445ca9ceb6d54028d2 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Wed, 3 Jun 2026 12:23:19 +0900 Subject: [PATCH 09/15] Updated --- Dockerfile | 2 +- .../configs/detection3d/dataset/t4dataset/j6gen2_base.py | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Dockerfile b/Dockerfile index 8867b972a..b265919b4 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,7 +61,7 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@076a6c7e98383f1e13df49fb3b83bc1d10124526 +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@91bc2f74347126d2cf7bd3d4fd9cee88f60268f6 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ diff --git a/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py b/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py index a9ba007d8..cc3a86d3e 100644 --- a/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py +++ b/autoware_ml/configs/detection3d/dataset/t4dataset/j6gen2_base.py @@ -34,8 +34,8 @@ dataset_test_groups = { "largebus": ("t4dataset_largebus_infos_test.pkl", False), - # "j6gen2": ("t4dataset_j6gen2_infos_test.pkl", False), - # "j6gen2_base": ("t4dataset_j6gen2_base_infos_test.pkl", True), + "j6gen2": ("t4dataset_j6gen2_infos_test.pkl", False), + "j6gen2_base": ("t4dataset_j6gen2_base_infos_test.pkl", True), } # dataset format setting From c8bb823dfd4690f481f7ceb41d696ef29fc381d4 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Wed, 3 Jun 2026 18:10:41 +0900 Subject: [PATCH 10/15] Updated --- Dockerfile | 2 +- autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py | 6 ++++++ ...l_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py | 2 +- 3 files changed, 8 insertions(+), 2 deletions(-) diff --git a/Dockerfile b/Dockerfile index b265919b4..7c31e3af3 100644 --- a/Dockerfile +++ b/Dockerfile @@ -61,7 +61,7 @@ RUN python3 -m pip --no-cache-dir install \ RUN python3 -m pip install git+https://github.com/tier4/t4-devkit@v0.5.1 # Install autoware-perception-evaluation -RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@91bc2f74347126d2cf7bd3d4fd9cee88f60268f6 +RUN python3 -m pip install git+https://github.com/tier4/autoware_perception_evaluation@85b78e52bca312911ea6730163dfeaa63c66c628 # Need to dowgrade setuptools to 60.2.0 to fix setup RUN python3 -m pip --no-cache-dir install \ diff --git a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py index c62af88a8..eb78024a9 100644 --- a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py +++ b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py @@ -1062,6 +1062,12 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato # Number of prediction matches (TPs) and matches at the optimal confidence threshold metric_dict[f"T4MetricV2_label/{label_name}_num-match_{matching_mode}_{threshold}"] = ap.num_tp + metric_dict[ + f"T4MetricV2_label/{label_name}_min-recall-num-match_{matching_mode}_{threshold}" + ] = ap.num_tp_at_min_recall_conf + metric_dict[ + f"T4MetricV2_label/{label_name}_medium-recall-num-match_{matching_mode}_{threshold}" + ] = ap.num_tp_at_medium_recall_conf metric_dict[ f"T4MetricV2_label/{label_name}_optimal-num-match_{matching_mode}_{threshold}" ] = ap.num_tp_at_optimal_conf diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py index 39462b1f6..c8892a9be 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py @@ -3,7 +3,7 @@ ] # user setting -experiment_group_name = "bevfusion_lidar_intensity/j6gen2_base/" + _base_.dataset_type +experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand_adjusted/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name From 6b33a80423cf51392cd3a8ac788a844e02fd10f4 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Thu, 4 Jun 2026 11:12:56 +0900 Subject: [PATCH 11/15] Updated --- ...voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py index c8892a9be..a41807fb0 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py @@ -3,7 +3,7 @@ ] # user setting -experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand_adjusted/" + _base_.dataset_type +experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_previous/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name From ab701c64715819477ca5db9e23c874e80e83d34e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 5 Jun 2026 03:32:41 +0000 Subject: [PATCH 12/15] ci(pre-commit): autofix --- .../datasets/transforms/__init__.py | 2 +- .../datasets/transforms/local_3d_bbox.py | 36 ++++++++--------- .../evaluation/t4metric/t4metric_v2.py | 40 ++++++++++--------- 3 files changed, 41 insertions(+), 37 deletions(-) diff --git a/autoware_ml/detection3d/datasets/transforms/__init__.py b/autoware_ml/detection3d/datasets/transforms/__init__.py index b20961db6..a63ff1eea 100644 --- a/autoware_ml/detection3d/datasets/transforms/__init__.py +++ b/autoware_ml/detection3d/datasets/transforms/__init__.py @@ -1,4 +1,4 @@ -from .object_min_points_filter import ObjectMinPointsFilter from .local_3d_bbox import Local3DBBoxExpand +from .object_min_points_filter import ObjectMinPointsFilter __all__ = ["ObjectMinPointsFilter", "Local3DBBoxExpand"] diff --git a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py index f35c8e7c0..cd340cbe1 100644 --- a/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py +++ b/autoware_ml/detection3d/datasets/transforms/local_3d_bbox.py @@ -1,7 +1,6 @@ from typing import List, Optional -import numpy as np - +import numpy as np from mmcv.transforms import BaseTransform from mmdet3d.structures.ops import box_np_ops from mmengine.registry import TRANSFORMS @@ -13,20 +12,21 @@ class Local3DBBoxExpand(BaseTransform): Args: expand_widths: (List[float]): Uniformly sampled expand width. - width_dim: (int): The dimension of the width. Default is 4, which is the width dimension of the 3D + width_dim: (int): The dimension of the width. Default is 4, which is the width dimension of the 3D bounding box. Since 3D Bbox is in the format of [x, y, z, dx, dy, dz, heading], the width dimension is the 4th dimension. label_ids: (List[int]): The label IDs to expand. If None, all label IDs will be expanded. - """ + """ def __init__( - self, - expand_widths: List[float], - expand_lengths: Optional[List[float]] = None, - length_dim: int = 3, - width_dim: int = 4, - label_ids: List[int] = None) -> None: - + self, + expand_widths: List[float], + expand_lengths: Optional[List[float]] = None, + length_dim: int = 3, + width_dim: int = 4, + label_ids: List[int] = None, + ) -> None: + super().__init__() assert isinstance(expand_widths, list) assert len(expand_widths) == 2 @@ -40,7 +40,7 @@ def __init__( self.expand_widths = expand_widths self.width_dim = width_dim self.label_ids = label_ids - + def transform(self, input_dict: dict) -> dict: """Call function to locally augment the 3D bounding boxes by scaling the width. @@ -51,22 +51,22 @@ def transform(self, input_dict: dict) -> dict: dict: Results after locally augmenting the 3D bounding boxes by scaling the width, 'gt_bboxes_3d' \ key is updated in the result dict. """ - # Label mask + # Label mask if self.label_ids is not None: - label_masks = [True if label in self.label_ids else False for label in input_dict["gt_labels_3d"]] + label_masks = [True if label in self.label_ids else False for label in input_dict["gt_labels_3d"]] else: label_masks = np.ones(len(input_dict["gt_labels_3d"]), dtype=bool) for i in range(len(input_dict["gt_bboxes_3d"])): if not label_masks[i]: - continue - + continue + expand_width = np.random.uniform(self.expand_widths[0], self.expand_widths[1]) input_dict["gt_bboxes_3d"].tensor[i, self.width_dim] += expand_width if self.expand_lengths is not None: expand_length = np.random.uniform(self.expand_lengths[0], self.expand_lengths[1]) input_dict["gt_bboxes_3d"].tensor[i, self.length_dim] += expand_length - + return input_dict def __repr__(self) -> str: @@ -74,4 +74,4 @@ def __repr__(self) -> str: repr_str = self.__class__.__name__ repr_str += f"(expand_widths={self.expand_widths}, expand_lengths={self.expand_lengths}, \ length_dim={self.length_dim}, width_dim={self.width_dim}, label_ids={self.label_ids})" - return repr_str \ No newline at end of file + return repr_str diff --git a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py index eb78024a9..f7f1af021 100644 --- a/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py +++ b/autoware_ml/detection3d/evaluation/t4metric/t4metric_v2.py @@ -994,7 +994,7 @@ def _aggregate_metrics_data( f"T4MetricV2_label_detection/{label_name}_interp-confs_{matching_mode}_{threshold}" ] = ap.conf_interp.tolist() - # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) + # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) if ap.tp_error_metrics is not None: for tp_error_metric in ap.tp_error_metrics: mode = tp_error_metric.mode @@ -1062,15 +1062,15 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato # Number of prediction matches (TPs) and matches at the optimal confidence threshold metric_dict[f"T4MetricV2_label/{label_name}_num-match_{matching_mode}_{threshold}"] = ap.num_tp - metric_dict[ - f"T4MetricV2_label/{label_name}_min-recall-num-match_{matching_mode}_{threshold}" - ] = ap.num_tp_at_min_recall_conf + metric_dict[f"T4MetricV2_label/{label_name}_min-recall-num-match_{matching_mode}_{threshold}"] = ( + ap.num_tp_at_min_recall_conf + ) metric_dict[ f"T4MetricV2_label/{label_name}_medium-recall-num-match_{matching_mode}_{threshold}" ] = ap.num_tp_at_medium_recall_conf - metric_dict[ - f"T4MetricV2_label/{label_name}_optimal-num-match_{matching_mode}_{threshold}" - ] = ap.num_tp_at_optimal_conf + metric_dict[f"T4MetricV2_label/{label_name}_optimal-num-match_{matching_mode}_{threshold}"] = ( + ap.num_tp_at_optimal_conf + ) # TP error metrics (e.g. ATE, AOE, ASE, AVE, AAE) if ap.tp_error_metrics is not None: @@ -1108,28 +1108,32 @@ def _process_metrics_for_aggregation(self, metrics_score: MetricsScore, evaluato if map_instance.mean_tp_errors is not None: for mean_tp_error_name, mean_tp_error_value in map_instance.mean_tp_errors.items(): metric_dict[f"T4MetricV2/mean-tp-error_{mean_tp_error_name}_{matching_mode}"] = mean_tp_error_value - + optimal_mean_tp_errors = map_instance.optimal_mean_tp_errors.get(mean_tp_error_name, None) if optimal_mean_tp_errors is not None: - metric_dict[f"T4MetricV2/mean-tp-error-optimal-{mean_tp_error_name}_{matching_mode}"] = optimal_mean_tp_errors - + metric_dict[f"T4MetricV2/mean-tp-error-optimal-{mean_tp_error_name}_{matching_mode}"] = ( + optimal_mean_tp_errors + ) + medium_mean_tp_errors = map_instance.medium_mean_tp_errors.get(mean_tp_error_name, None) if medium_mean_tp_errors is not None: - metric_dict[f"T4MetricV2/mean-tp-error-medium-{mean_tp_error_name}_{matching_mode}"] = medium_mean_tp_errors - + metric_dict[f"T4MetricV2/mean-tp-error-medium-{mean_tp_error_name}_{matching_mode}"] = ( + medium_mean_tp_errors + ) + # Add NuScenes Detection Score (NDS) based on mAP and mAPH if map_instance.map_based_nds is not None: - metric_dict[ - f"T4MetricV2/{map_instance.map_based_nds.metric_prefix_name}_nds_{matching_mode}" - ] = map_instance.map_based_nds.nds + metric_dict[f"T4MetricV2/{map_instance.map_based_nds.metric_prefix_name}_nds_{matching_mode}"] = ( + map_instance.map_based_nds.nds + ) if map_instance.medium_map_based_nds is not None: metric_dict[ f"T4MetricV2/{map_instance.medium_map_based_nds.metric_prefix_name}_nds_{matching_mode}" ] = map_instance.medium_map_based_nds.nds if map_instance.mapH_based_nds is not None: - metric_dict[ - f"T4MetricV2/{map_instance.mapH_based_nds.metric_prefix_name}_nds_{matching_mode}" - ] = map_instance.mapH_based_nds.nds + metric_dict[f"T4MetricV2/{map_instance.mapH_based_nds.metric_prefix_name}_nds_{matching_mode}"] = ( + map_instance.mapH_based_nds.nds + ) if map_instance.medium_mapH_based_nds is not None: metric_dict[ f"T4MetricV2/{map_instance.medium_mapH_based_nds.metric_prefix_name}_nds_{matching_mode}" From c306ad1d1fced0ca43ad351fd8f54fd503c234bd Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Fri, 5 Jun 2026 12:34:55 +0900 Subject: [PATCH 13/15] Resolve config --- ..._second_secfpn_30e_8xb8_j6gen2_base_120m.py | 8 +++----- ...pn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py | 2 +- ...r_voxel_second_secfpn_50e_8xb8_base_120m.py | 2 +- .../default/pipelines/default_lidar_120m.py | 18 ------------------ .../pipelines/default_lidar_intensity_120m.py | 18 ------------------ tools/detection3d/test.py | 2 +- 6 files changed, 6 insertions(+), 44 deletions(-) diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py index f3646781a..d32dc9c70 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m.py @@ -13,11 +13,9 @@ # user setting data_root = "data/t4dataset/" -info_directory_path = "info/kokseang_2_7/" +info_directory_path = "info/user_name/" -experiment_group_name = ( - "bevfusion_lidar_intensity_2_7_1/j6gen2_base_with_bbox_expand_adjusted_test/" + _base_.dataset_type -) +experiment_group_name = "bevfusion_lidar_intensity/j6gen2_base/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name @@ -166,4 +164,4 @@ ) log_processor = dict(window_size=50) -load_from = "work_dirs/bevfusion_lidar_2.7.0/base/epoch_48.pth" +load_from = None diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py index 138cb6892..260080bc6 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2.py @@ -3,7 +3,7 @@ ] # user setting -experiment_group_name = "bevfusion_lidar_intensity_2_7_1/j6gen2_base_previous/" + _base_.dataset_type +experiment_group_name = "bevfusion_lidar_intensity/j6gen2_base/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_30e_8xb8_j6gen2_base_120m_t4metric_v2" work_dir = "work_dirs/" + experiment_group_name + "/" + experiment_name diff --git a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py index 56f19d5a7..e8068332a 100644 --- a/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py +++ b/projects/BEVFusion/configs/t4dataset/BEVFusion-L/bevfusion_lidar_voxel_second_secfpn_50e_8xb8_base_120m.py @@ -13,7 +13,7 @@ # user setting data_root = "data/t4dataset/" -info_directory_path = "info/kokseang_2_7/" +info_directory_path = "info/user_name/" experiment_group_name = "bevfusion_lidar/base/" + _base_.dataset_type experiment_name = "lidar_voxel_second_secfpn_50e_8xb8_base_120m" diff --git a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py index 23ae03ea0..09b9f7b26 100644 --- a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py +++ b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_120m.py @@ -42,24 +42,6 @@ test_mode=False, ), dict(type="LoadAnnotations3D", with_bbox_3d=True, with_label_3d=True, with_attr_label=False), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.20, 0.40], # 10cm - 20cm to each side - label_ids=[0], # car - expand_lengths=None, # no expand - ), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.50, 0.80], # 25cm - 40cm to each side - label_ids=[1], # trucks - expand_lengths=[0.4, 0.60], # 20cm - 30cm to each side - ), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.5, 0.8], # 25cm - 40cm to each side - label_ids=[2], # buses - expand_lengths=[0.5, 0.9], # 25cm - 45cm to each side - ), dict( type="BEVFusionGlobalRotScaleTrans", scale_ratio_range=[0.95, 1.05], diff --git a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py index 083457572..e2de195e9 100644 --- a/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py +++ b/projects/BEVFusion/configs/t4dataset/default/pipelines/default_lidar_intensity_120m.py @@ -42,24 +42,6 @@ test_mode=False, ), dict(type="LoadAnnotations3D", with_bbox_3d=True, with_label_3d=True, with_attr_label=False), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.20, 0.40], # 10cm - 20cm to each side - label_ids=[0], # car - expand_lengths=None, # no expand - ), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.50, 0.80], # 25cm - 40cm to each side - label_ids=[1], # trucks - expand_lengths=[0.4, 0.60], # 20cm - 30cm to each side - ), - dict( - type="Local3DBBoxExpand", - expand_widths=[0.5, 0.8], # 25cm - 40cm to each side - label_ids=[2], # buses - expand_lengths=[0.5, 0.9], # 25cm - 45cm to each side - ), dict( type="BEVFusionGlobalRotScaleTrans", scale_ratio_range=[0.95, 1.05], diff --git a/tools/detection3d/test.py b/tools/detection3d/test.py index 0f609ed5a..64489fbaa 100644 --- a/tools/detection3d/test.py +++ b/tools/detection3d/test.py @@ -129,7 +129,7 @@ def main(): dataset_file, evaluate_frame_prefix = dataset_configs cfg.test_dataloader.dataset.ann_file = osp.join(cfg.info_directory_path, dataset_file) cfg.test_evaluator.dataset_name = dataset_name - # cfg.test_evaluator.evaluate_frame_prefix = evaluate_frame_prefix + cfg.test_evaluator.evaluate_frame_prefix = evaluate_frame_prefix cfg.test_evaluator.ann_file = osp.join(cfg.data_root, cfg.info_directory_path, dataset_file) # build the runner from config From 75744a5e4026aa793068a6888a7dd291027b043b Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Fri, 5 Jun 2026 12:35:53 +0900 Subject: [PATCH 14/15] Resolve config --- tools/detection3d/t4dataset_converters/t4converter.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/tools/detection3d/t4dataset_converters/t4converter.py b/tools/detection3d/t4dataset_converters/t4converter.py index b988037e5..e52443676 100644 --- a/tools/detection3d/t4dataset_converters/t4converter.py +++ b/tools/detection3d/t4dataset_converters/t4converter.py @@ -627,10 +627,6 @@ def get_lidarseg_annotations( if not hasattr(t4, "lidarseg") or not t4.lidarseg: return dict() - if sd_record.info_filename is None: - print(f"sample {lidar_token} doesn't have lidar info_filename") - return dict() - assert i < len(t4.lidarseg), "Index exceeds number of lidarseg records!" if sd_record.info_filename is None: print(f"sample {lidar_token} doesn't have lidar info_filename") From 0e4328647f49b01ef12734833036fb5eda75fe04 Mon Sep 17 00:00:00 2001 From: Kok Seang Tan Date: Fri, 5 Jun 2026 12:37:23 +0900 Subject: [PATCH 15/15] Resolve config --- tools/detection3d/t4dataset_converters/t4converter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/detection3d/t4dataset_converters/t4converter.py b/tools/detection3d/t4dataset_converters/t4converter.py index e52443676..ccc88b2d1 100644 --- a/tools/detection3d/t4dataset_converters/t4converter.py +++ b/tools/detection3d/t4dataset_converters/t4converter.py @@ -627,11 +627,11 @@ def get_lidarseg_annotations( if not hasattr(t4, "lidarseg") or not t4.lidarseg: return dict() - assert i < len(t4.lidarseg), "Index exceeds number of lidarseg records!" if sd_record.info_filename is None: print(f"sample {lidar_token} doesn't have lidar info_filename") return dict() + assert i < len(t4.lidarseg), "Index exceeds number of lidarseg records!" assert t4.lidarseg[i].sample_data_token == lidar_token, "Sample data token mismatch!" return dict( pts_semantic_mask_path=parse_lidar_path(osp.join(t4.data_root, t4.lidarseg[i].filename)),