From 3f9e29395eab3eb40291edb62e6453857969b6fb Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 25 Dec 2025 17:28:05 +0900 Subject: [PATCH 01/16] feat: integrate centerpoint to new deployment framework Signed-off-by: vividf --- deployment/projects/centerpoint/__init__.py | 22 ++ deployment/projects/centerpoint/cli.py | 14 ++ .../centerpoint/config/deploy_config.py | 160 ++++++++++++++ .../projects/centerpoint/data_loader.py | 200 ++++++++++++++++++ deployment/projects/centerpoint/entrypoint.py | 59 ++++++ deployment/projects/centerpoint/evaluator.py | 172 +++++++++++++++ .../centerpoint/export/component_extractor.py | 120 +++++++++++ .../export/onnx_export_pipeline.py | 128 +++++++++++ .../export/tensorrt_export_pipeline.py | 103 +++++++++ .../projects/centerpoint/model_loader.py | 144 +++++++++++++ .../centerpoint/onnx_models/__init__.py | 28 +++ .../onnx_models}/centerpoint_head_onnx.py | 8 +- .../onnx_models/centerpoint_onnx.py | 147 +++++++++++++ .../onnx_models}/pillar_encoder_onnx.py | 8 +- .../pipelines/centerpoint_pipeline.py | 157 ++++++++++++++ .../projects/centerpoint/pipelines/factory.py | 64 ++++++ .../projects/centerpoint/pipelines/onnx.py | 86 ++++++++ .../projects/centerpoint/pipelines/pytorch.py | 87 ++++++++ .../centerpoint/pipelines/tensorrt.py | 178 ++++++++++++++++ deployment/projects/centerpoint/runner.py | 99 +++++++++ projects/CenterPoint/Dockerfile | 13 ++ projects/CenterPoint/README.md | 15 +- projects/CenterPoint/models/__init__.py | 8 - .../models/detectors/centerpoint_onnx.py | 176 --------------- .../CenterPoint/runners/deployment_runner.py | 103 --------- projects/CenterPoint/scripts/deploy.py | 87 -------- 26 files changed, 2006 insertions(+), 380 deletions(-) create mode 100644 deployment/projects/centerpoint/__init__.py create mode 100644 deployment/projects/centerpoint/cli.py create mode 100644 deployment/projects/centerpoint/config/deploy_config.py create mode 100644 deployment/projects/centerpoint/data_loader.py create mode 100644 deployment/projects/centerpoint/entrypoint.py create mode 100644 deployment/projects/centerpoint/evaluator.py create mode 100644 deployment/projects/centerpoint/export/component_extractor.py create mode 100644 deployment/projects/centerpoint/export/onnx_export_pipeline.py create mode 100644 deployment/projects/centerpoint/export/tensorrt_export_pipeline.py create mode 100644 deployment/projects/centerpoint/model_loader.py create mode 100644 deployment/projects/centerpoint/onnx_models/__init__.py rename {projects/CenterPoint/models/dense_heads => deployment/projects/centerpoint/onnx_models}/centerpoint_head_onnx.py (95%) create mode 100644 deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py rename {projects/CenterPoint/models/voxel_encoders => deployment/projects/centerpoint/onnx_models}/pillar_encoder_onnx.py (96%) create mode 100644 deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py create mode 100644 deployment/projects/centerpoint/pipelines/factory.py create mode 100644 deployment/projects/centerpoint/pipelines/onnx.py create mode 100644 deployment/projects/centerpoint/pipelines/pytorch.py create mode 100644 deployment/projects/centerpoint/pipelines/tensorrt.py create mode 100644 deployment/projects/centerpoint/runner.py create mode 100644 projects/CenterPoint/Dockerfile delete mode 100644 projects/CenterPoint/models/detectors/centerpoint_onnx.py delete mode 100644 projects/CenterPoint/runners/deployment_runner.py delete mode 100644 projects/CenterPoint/scripts/deploy.py diff --git a/deployment/projects/centerpoint/__init__.py b/deployment/projects/centerpoint/__init__.py new file mode 100644 index 000000000..e7cae0e0c --- /dev/null +++ b/deployment/projects/centerpoint/__init__.py @@ -0,0 +1,22 @@ +"""CenterPoint deployment bundle. + +This package owns all CenterPoint deployment-specific code (runner/evaluator/loader/pipelines/export). +It registers a ProjectAdapter into the global `project_registry` so the unified CLI can invoke it. +""" + +from __future__ import annotations + +from deployment.projects.centerpoint.cli import add_args +from deployment.projects.centerpoint.entrypoint import run + +# Trigger pipeline factory registration for this project. +from deployment.projects.centerpoint.pipelines.factory import CenterPointPipelineFactory # noqa: F401 +from deployment.projects.registry import ProjectAdapter, project_registry + +project_registry.register( + ProjectAdapter( + name="centerpoint", + add_args=add_args, + run=run, + ) +) diff --git a/deployment/projects/centerpoint/cli.py b/deployment/projects/centerpoint/cli.py new file mode 100644 index 000000000..cc040e0d9 --- /dev/null +++ b/deployment/projects/centerpoint/cli.py @@ -0,0 +1,14 @@ +"""CenterPoint CLI extensions.""" + +from __future__ import annotations + +import argparse + + +def add_args(parser: argparse.ArgumentParser) -> None: + """Register CenterPoint-specific CLI flags onto a project subparser.""" + parser.add_argument( + "--rot-y-axis-reference", + action="store_true", + help="Convert rotation to y-axis clockwise reference (CenterPoint ONNX-compatible format)", + ) diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py new file mode 100644 index 000000000..e270b3b27 --- /dev/null +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -0,0 +1,160 @@ +""" +CenterPoint Deployment Configuration + +NOTE: This file was moved under deployment/projects/centerpoint/config/ as part of the +proposed unified deployment architecture. +""" + +# ============================================================================ +# Task type for pipeline building +# Options: 'detection2d', 'detection3d', 'classification', 'segmentation' +# ============================================================================ +task_type = "detection3d" + +# ============================================================================ +# Checkpoint Path - Single source of truth for PyTorch model +# ============================================================================ +checkpoint_path = "work_dirs/centerpoint/best_checkpoint.pth" + +# ============================================================================ +# Device settings (shared by export, evaluation, verification) +# ============================================================================ +devices = dict( + cpu="cpu", + cuda="cuda:0", +) + +# ============================================================================ +# Export Configuration +# ============================================================================ +export = dict( + mode="both", + work_dir="work_dirs/centerpoint_deployment", + onnx_path=None, +) + +# ============================================================================ +# Runtime I/O settings +# ============================================================================ +runtime_io = dict( + info_file="data/t4dataset/info/t4dataset_j6gen2_infos_val.pkl", + sample_idx=1, +) + +# ============================================================================ +# Model Input/Output Configuration +# ============================================================================ +model_io = dict( + input_name="voxels", + input_shape=(32, 4), + input_dtype="float32", + additional_inputs=[ + dict(name="num_points", shape=(-1,), dtype="int32"), + dict(name="coors", shape=(-1, 4), dtype="int32"), + ], + head_output_names=("heatmap", "reg", "height", "dim", "rot", "vel"), + batch_size=None, + dynamic_axes={ + "voxels": {0: "num_voxels"}, + "num_points": {0: "num_voxels"}, + "coors": {0: "num_voxels"}, + }, +) + +# ============================================================================ +# ONNX Export Configuration +# ============================================================================ +onnx_config = dict( + opset_version=16, + do_constant_folding=True, + export_params=True, + keep_initializers_as_inputs=False, + simplify=False, + multi_file=True, + components=dict( + voxel_encoder=dict( + name="pts_voxel_encoder", + onnx_file="pts_voxel_encoder.onnx", + engine_file="pts_voxel_encoder.engine", + ), + backbone_head=dict( + name="pts_backbone_neck_head", + onnx_file="pts_backbone_neck_head.onnx", + engine_file="pts_backbone_neck_head.engine", + ), + ), +) + +# ============================================================================ +# Backend Configuration (mainly for TensorRT) +# ============================================================================ +backend_config = dict( + common_config=dict( + precision_policy="auto", + max_workspace_size=2 << 30, + ), + model_inputs=[ + dict( + input_shapes=dict( + input_features=dict( + min_shape=[1000, 32, 11], + opt_shape=[20000, 32, 11], + max_shape=[64000, 32, 11], + ), + spatial_features=dict( + min_shape=[1, 32, 760, 760], + opt_shape=[1, 32, 760, 760], + max_shape=[1, 32, 760, 760], + ), + ) + ) + ], +) + +# ============================================================================ +# Evaluation Configuration +# ============================================================================ +evaluation = dict( + enabled=True, + num_samples=1, + verbose=True, + backends=dict( + pytorch=dict( + enabled=True, + device=devices["cuda"], + ), + onnx=dict( + enabled=True, + device=devices["cuda"], + model_dir="work_dirs/centerpoint_deployment/onnx/", + ), + tensorrt=dict( + enabled=True, + device=devices["cuda"], + engine_dir="work_dirs/centerpoint_deployment/tensorrt/", + ), + ), +) + +# ============================================================================ +# Verification Configuration +# ============================================================================ +verification = dict( + enabled=False, + tolerance=1e-1, + num_verify_samples=1, + devices=devices, + scenarios=dict( + both=[ + dict(ref_backend="pytorch", ref_device="cpu", test_backend="onnx", test_device="cpu"), + dict(ref_backend="onnx", ref_device="cuda", test_backend="tensorrt", test_device="cuda"), + ], + onnx=[ + dict(ref_backend="pytorch", ref_device="cpu", test_backend="onnx", test_device="cpu"), + ], + trt=[ + dict(ref_backend="onnx", ref_device="cuda", test_backend="tensorrt", test_device="cuda"), + ], + none=[], + ), +) diff --git a/deployment/projects/centerpoint/data_loader.py b/deployment/projects/centerpoint/data_loader.py new file mode 100644 index 000000000..0c713a3ea --- /dev/null +++ b/deployment/projects/centerpoint/data_loader.py @@ -0,0 +1,200 @@ +""" +CenterPoint DataLoader for deployment. + +Moved from projects/CenterPoint/deploy/data_loader.py into the unified deployment bundle. +""" + +import os +import pickle +from typing import Any, Dict, List, Optional, Union + +import numpy as np +import torch +from mmengine.config import Config + +from deployment.core import BaseDataLoader, build_preprocessing_pipeline + + +class CenterPointDataLoader(BaseDataLoader): + """Deployment dataloader for CenterPoint. + + Responsibilities: + - Load `info_file` (pickle) entries describing samples. + - Build and run the MMEngine preprocessing pipeline for each sample. + - Provide `load_sample()` for export helpers that need raw sample metadata. + """ + + def __init__( + self, + info_file: str, + model_cfg: Config, + device: str = "cpu", + task_type: Optional[str] = None, + ): + super().__init__( + config={ + "info_file": info_file, + "device": device, + } + ) + + if not os.path.exists(info_file): + raise FileNotFoundError(f"Info file not found: {info_file}") + + self.info_file = info_file + self.model_cfg = model_cfg + self.device = device + + self.data_infos = self._load_info_file() + self.pipeline = build_preprocessing_pipeline(model_cfg, task_type=task_type) + + def _to_tensor( + self, + data: Union[torch.Tensor, np.ndarray, List[Union[torch.Tensor, np.ndarray]]], + name: str = "data", + ) -> torch.Tensor: + if isinstance(data, torch.Tensor): + return data.to(self.device) + + if isinstance(data, np.ndarray): + return torch.from_numpy(data).to(self.device) + + if isinstance(data, list): + if len(data) == 0: + raise ValueError(f"Empty list for '{name}' in pipeline output.") + + first_item = data[0] + if isinstance(first_item, torch.Tensor): + return first_item.to(self.device) + if isinstance(first_item, np.ndarray): + return torch.from_numpy(first_item).to(self.device) + + raise ValueError( + f"Unexpected type for {name}[0]: {type(first_item)}. Expected torch.Tensor or np.ndarray." + ) + + raise ValueError( + f"Unexpected type for '{name}': {type(data)}. Expected torch.Tensor, np.ndarray, or list of tensors/arrays." + ) + + def _load_info_file(self) -> list: + try: + with open(self.info_file, "rb") as f: + data = pickle.load(f) + except Exception as e: + raise ValueError(f"Failed to load info file: {e}") from e + + if isinstance(data, dict): + if "data_list" in data: + data_list = data["data_list"] + elif "infos" in data: + data_list = data["infos"] + else: + raise ValueError(f"Expected 'data_list' or 'infos' in info file, found keys: {list(data.keys())}") + elif isinstance(data, list): + data_list = data + else: + raise ValueError(f"Unexpected info file format: {type(data)}") + + if not data_list: + raise ValueError("No samples found in info file") + + return data_list + + def load_sample(self, index: int) -> Dict[str, Any]: + if index >= len(self.data_infos): + raise IndexError(f"Sample index {index} out of range (0-{len(self.data_infos)-1})") + + info = self.data_infos[index] + + lidar_points = info.get("lidar_points", {}) + if not lidar_points: + lidar_path = info.get("lidar_path", info.get("velodyne_path", "")) + lidar_points = {"lidar_path": lidar_path} + + if "lidar_path" in lidar_points and not lidar_points["lidar_path"].startswith("/"): + data_root = getattr(self.model_cfg, "data_root", "data/t4dataset/") + if not data_root.endswith("/"): + data_root += "/" + if not lidar_points["lidar_path"].startswith(data_root): + lidar_points["lidar_path"] = data_root + lidar_points["lidar_path"] + + instances = info.get("instances", []) + + sample = { + "lidar_points": lidar_points, + "sample_idx": info.get("sample_idx", index), + "timestamp": info.get("timestamp", 0), + } + + if instances: + gt_bboxes_3d = [] + gt_labels_3d = [] + + for instance in instances: + if "bbox_3d" in instance and "bbox_label_3d" in instance: + if instance.get("bbox_3d_isvalid", True): + gt_bboxes_3d.append(instance["bbox_3d"]) + gt_labels_3d.append(instance["bbox_label_3d"]) + + if gt_bboxes_3d: + sample["gt_bboxes_3d"] = np.array(gt_bboxes_3d, dtype=np.float32) + sample["gt_labels_3d"] = np.array(gt_labels_3d, dtype=np.int64) + + if "images" in info or "img_path" in info: + sample["images"] = info.get("images", {}) + if "img_path" in info: + sample["img_path"] = info["img_path"] + + return sample + + def preprocess(self, sample: Dict[str, Any]) -> Union[Dict[str, torch.Tensor], torch.Tensor]: + results = self.pipeline(sample) + + if "inputs" not in results: + raise ValueError( + "Expected 'inputs' key in pipeline results (MMDet3D 3.x format). " + f"Found keys: {list(results.keys())}. " + "Please ensure your test pipeline includes Pack3DDetInputs transform." + ) + + pipeline_inputs = results["inputs"] + if "points" not in pipeline_inputs: + available_keys = list(pipeline_inputs.keys()) + raise ValueError( + "Expected 'points' key in pipeline inputs for CenterPoint. " + f"Available keys: {available_keys}. " + "For CenterPoint, voxelization is performed by the model's data_preprocessor." + ) + + points_tensor = self._to_tensor(pipeline_inputs["points"], name="points") + if points_tensor.ndim != 2: + raise ValueError(f"Expected points tensor with shape [N, point_features], got shape {points_tensor.shape}") + + return {"points": points_tensor} + + def get_num_samples(self) -> int: + return len(self.data_infos) + + def get_ground_truth(self, index: int) -> Dict[str, Any]: + sample = self.load_sample(index) + + gt_bboxes_3d = sample.get("gt_bboxes_3d", np.zeros((0, 7), dtype=np.float32)) + gt_labels_3d = sample.get("gt_labels_3d", np.zeros((0,), dtype=np.int64)) + + if isinstance(gt_bboxes_3d, (list, tuple)): + gt_bboxes_3d = np.array(gt_bboxes_3d, dtype=np.float32) + if isinstance(gt_labels_3d, (list, tuple)): + gt_labels_3d = np.array(gt_labels_3d, dtype=np.int64) + + return { + "gt_bboxes_3d": gt_bboxes_3d, + "gt_labels_3d": gt_labels_3d, + "sample_idx": sample.get("sample_idx", index), + } + + def get_class_names(self) -> List[str]: + if hasattr(self.model_cfg, "class_names"): + return self.model_cfg.class_names + + raise ValueError("class_names must be defined in model_cfg.") diff --git a/deployment/projects/centerpoint/entrypoint.py b/deployment/projects/centerpoint/entrypoint.py new file mode 100644 index 000000000..2fd6a7022 --- /dev/null +++ b/deployment/projects/centerpoint/entrypoint.py @@ -0,0 +1,59 @@ +"""CenterPoint deployment entrypoint invoked by the unified CLI.""" + +from __future__ import annotations + +import logging + +from mmengine.config import Config + +from deployment.core.config.base_config import BaseDeploymentConfig, setup_logging +from deployment.core.contexts import CenterPointExportContext +from deployment.core.metrics.detection_3d_metrics import Detection3DMetricsConfig +from deployment.projects.centerpoint.data_loader import CenterPointDataLoader +from deployment.projects.centerpoint.evaluator import CenterPointEvaluator +from deployment.projects.centerpoint.model_loader import extract_t4metric_v2_config +from deployment.projects.centerpoint.runner import CenterPointDeploymentRunner + + +def run(args) -> int: + """Run the CenterPoint deployment workflow for the unified CLI. + + This wires together the CenterPoint bundle components (data loader, evaluator, + runner) and executes export/verification/evaluation according to `deploy_cfg`. + """ + logger = setup_logging(args.log_level) + + deploy_cfg = Config.fromfile(args.deploy_cfg) + model_cfg = Config.fromfile(args.model_cfg) + config = BaseDeploymentConfig(deploy_cfg) + + logger.info("=" * 80) + logger.info("CenterPoint Deployment Pipeline (Unified CLI)") + logger.info("=" * 80) + + data_loader = CenterPointDataLoader( + info_file=config.runtime_config.info_file, + model_cfg=model_cfg, + device="cpu", + task_type=config.task_type, + ) + logger.info(f"Loaded {data_loader.get_num_samples()} samples") + + metrics_config = extract_t4metric_v2_config(model_cfg, logger=logger) + + evaluator = CenterPointEvaluator( + model_cfg=model_cfg, + metrics_config=metrics_config, + ) + + runner = CenterPointDeploymentRunner( + data_loader=data_loader, + evaluator=evaluator, + config=config, + model_cfg=model_cfg, + logger=logger, + ) + + context = CenterPointExportContext(rot_y_axis_reference=bool(getattr(args, "rot_y_axis_reference", False))) + runner.run(context=context) + return 0 diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py new file mode 100644 index 000000000..60f1df90e --- /dev/null +++ b/deployment/projects/centerpoint/evaluator.py @@ -0,0 +1,172 @@ +""" +CenterPoint Evaluator for deployment. + +Moved from projects/CenterPoint/deploy/evaluator.py into the unified deployment bundle. +""" + +import logging +from typing import Any, Dict, List, Tuple + +from mmengine.config import Config + +from deployment.core import ( + BaseEvaluator, + Detection3DMetricsConfig, + Detection3DMetricsInterface, + EvalResultDict, + ModelSpec, + TaskProfile, +) +from deployment.core.io.base_data_loader import BaseDataLoader +from deployment.pipelines.factory import PipelineFactory +from deployment.projects.centerpoint.config.deploy_config import model_io + +logger = logging.getLogger(__name__) + + +class CenterPointEvaluator(BaseEvaluator): + """Evaluator implementation for CenterPoint 3D detection. + + This builds a task profile (class names, display name) and uses the configured + `Detection3DMetricsInterface` to compute metrics from pipeline outputs. + """ + + def __init__( + self, + model_cfg: Config, + metrics_config: Detection3DMetricsConfig, + ): + if hasattr(model_cfg, "class_names"): + class_names = model_cfg.class_names + else: + raise ValueError("class_names must be provided via model_cfg.class_names.") + + task_profile = TaskProfile( + task_name="centerpoint_3d_detection", + display_name="CenterPoint 3D Object Detection", + class_names=tuple(class_names), + num_classes=len(class_names), + ) + + metrics_interface = Detection3DMetricsInterface(metrics_config) + + super().__init__( + metrics_interface=metrics_interface, + task_profile=task_profile, + model_cfg=model_cfg, + ) + + def set_onnx_config(self, model_cfg: Config) -> None: + self.model_cfg = model_cfg + + def _get_output_names(self) -> List[str]: + return list(model_io["head_output_names"]) + + def _create_pipeline(self, model_spec: ModelSpec, device: str) -> Any: + return PipelineFactory.create( + project_name="centerpoint", + model_spec=model_spec, + pytorch_model=self.pytorch_model, + device=device, + ) + + def _prepare_input( + self, + sample: Dict[str, Any], + data_loader: BaseDataLoader, + device: str, + ) -> Tuple[Any, Dict[str, Any]]: + if "points" in sample: + points = sample["points"] + else: + input_data = data_loader.preprocess(sample) + points = input_data.get("points", input_data) + + metadata = sample.get("metainfo", {}) + return points, metadata + + def _parse_predictions(self, pipeline_output: Any) -> List[Dict]: + return pipeline_output if isinstance(pipeline_output, list) else [] + + def _parse_ground_truths(self, gt_data: Dict[str, Any]) -> List[Dict]: + ground_truths = [] + + if "gt_bboxes_3d" in gt_data and "gt_labels_3d" in gt_data: + gt_bboxes_3d = gt_data["gt_bboxes_3d"] + gt_labels_3d = gt_data["gt_labels_3d"] + + for i in range(len(gt_bboxes_3d)): + ground_truths.append({"bbox_3d": gt_bboxes_3d[i].tolist(), "label": int(gt_labels_3d[i])}) + + return ground_truths + + def _add_to_interface(self, predictions: List[Dict], ground_truths: List[Dict]) -> None: + self.metrics_interface.add_frame(predictions, ground_truths) + + def _build_results( + self, + latencies: List[float], + latency_breakdowns: List[Dict[str, float]], + num_samples: int, + ) -> EvalResultDict: + latency_stats = self.compute_latency_stats(latencies) + latency_payload = latency_stats.to_dict() + + if latency_breakdowns: + latency_payload["latency_breakdown"] = self._compute_latency_breakdown(latency_breakdowns).to_dict() + + map_results = self.metrics_interface.compute_metrics() + summary = self.metrics_interface.get_summary() + summary_dict = summary.to_dict() if hasattr(summary, "to_dict") else summary + + return { + "mAP": summary_dict.get("mAP", 0.0), + "mAPH": summary_dict.get("mAPH", 0.0), + "per_class_ap": summary_dict.get("per_class_ap", {}), + "detailed_metrics": map_results, + "latency": latency_payload, + "num_samples": num_samples, + } + + def print_results(self, results: EvalResultDict) -> None: + print("\n" + "=" * 80) + print(f"{self.task_profile.display_name} - Evaluation Results") + print("(Using autoware_perception_evaluation for consistent metrics)") + print("=" * 80) + + print("\nDetection Metrics:") + print(f" mAP: {results.get('mAP', 0.0):.4f}") + print(f" mAPH: {results.get('mAPH', 0.0):.4f}") + + if "per_class_ap" in results: + print("\nPer-Class AP:") + for class_id, ap in results["per_class_ap"].items(): + class_name = ( + class_id + if isinstance(class_id, str) + else (self.class_names[class_id] if class_id < len(self.class_names) else f"class_{class_id}") + ) + print(f" {class_name:<12}: {ap:.4f}") + + if "latency" in results: + latency = results["latency"] + print("\nLatency Statistics:") + print(f" Mean: {latency['mean_ms']:.2f} ms") + print(f" Std: {latency['std_ms']:.2f} ms") + print(f" Min: {latency['min_ms']:.2f} ms") + print(f" Max: {latency['max_ms']:.2f} ms") + print(f" Median: {latency['median_ms']:.2f} ms") + + if "latency_breakdown" in latency: + breakdown = latency["latency_breakdown"] + print("\nStage-wise Latency Breakdown:") + model_substages = {"voxel_encoder_ms", "middle_encoder_ms", "backbone_head_ms"} + for stage, stats in breakdown.items(): + stage_name = stage.replace("_ms", "").replace("_", " ").title() + if stage in model_substages: + print(f" {stage_name:16s}: {stats['mean_ms']:.2f} ± {stats['std_ms']:.2f} ms") + else: + print(f" {stage_name:18s}: {stats['mean_ms']:.2f} ± {stats['std_ms']:.2f} ms") + + print(f"\nTotal Samples: {results.get('num_samples', 0)}") + print("=" * 80) diff --git a/deployment/projects/centerpoint/export/component_extractor.py b/deployment/projects/centerpoint/export/component_extractor.py new file mode 100644 index 000000000..5c5aed120 --- /dev/null +++ b/deployment/projects/centerpoint/export/component_extractor.py @@ -0,0 +1,120 @@ +""" +CenterPoint-specific component extractor. + +Moved from projects/CenterPoint/deploy/component_extractor.py into the unified deployment bundle. +""" + +import logging +from typing import Any, List, Tuple + +import torch + +from deployment.exporters.common.configs import ONNXExportConfig +from deployment.exporters.export_pipelines.interfaces import ExportableComponent, ModelComponentExtractor +from deployment.projects.centerpoint.config.deploy_config import model_io, onnx_config +from deployment.projects.centerpoint.onnx_models.centerpoint_onnx import CenterPointHeadONNX + +logger = logging.getLogger(__name__) + + +class CenterPointComponentExtractor(ModelComponentExtractor): + """Extract exportable CenterPoint submodules for multi-file ONNX export. + + For CenterPoint we export two components: + - `voxel_encoder` (pts_voxel_encoder) + - `backbone_neck_head` (pts_backbone + pts_neck + pts_bbox_head) + """ + + def __init__(self, logger: logging.Logger = None, simplify: bool = True): + self.logger = logger or logging.getLogger(__name__) + self.simplify = simplify + + def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[ExportableComponent]: + input_features, voxel_dict = sample_data + self.logger.info("Extracting CenterPoint components for export...") + + voxel_component = self._create_voxel_encoder_component(model, input_features) + backbone_component = self._create_backbone_component(model, input_features, voxel_dict) + + self.logger.info("Extracted 2 components: voxel_encoder, backbone_neck_head") + return [voxel_component, backbone_component] + + def _create_voxel_encoder_component( + self, model: torch.nn.Module, input_features: torch.Tensor + ) -> ExportableComponent: + voxel_cfg = onnx_config["components"]["voxel_encoder"] + return ExportableComponent( + name=voxel_cfg["name"], + module=model.pts_voxel_encoder, + sample_input=input_features, + config_override=ONNXExportConfig( + input_names=("input_features",), + output_names=("pillar_features",), + dynamic_axes={ + "input_features": {0: "num_voxels", 1: "num_max_points"}, + "pillar_features": {0: "num_voxels"}, + }, + opset_version=16, + do_constant_folding=True, + simplify=self.simplify, + save_file=voxel_cfg["onnx_file"], + ), + ) + + def _create_backbone_component( + self, model: torch.nn.Module, input_features: torch.Tensor, voxel_dict: dict + ) -> ExportableComponent: + backbone_input = self._prepare_backbone_input(model, input_features, voxel_dict) + backbone_module = self._create_backbone_module(model) + output_names = self._get_output_names(model) + + dynamic_axes = { + "spatial_features": {0: "batch_size", 2: "height", 3: "width"}, + } + for name in output_names: + dynamic_axes[name] = {0: "batch_size", 2: "height", 3: "width"} + + backbone_cfg = onnx_config["components"]["backbone_head"] + return ExportableComponent( + name=backbone_cfg["name"], + module=backbone_module, + sample_input=backbone_input, + config_override=ONNXExportConfig( + input_names=("spatial_features",), + output_names=output_names, + dynamic_axes=dynamic_axes, + opset_version=16, + do_constant_folding=True, + simplify=self.simplify, + save_file=backbone_cfg["onnx_file"], + ), + ) + + def _prepare_backbone_input( + self, model: torch.nn.Module, input_features: torch.Tensor, voxel_dict: dict + ) -> torch.Tensor: + with torch.no_grad(): + voxel_features = model.pts_voxel_encoder(input_features).squeeze(1) + coors = voxel_dict["coors"] + batch_size = int(coors[-1, 0].item()) + 1 if len(coors) > 0 else 1 + spatial_features = model.pts_middle_encoder(voxel_features, coors, batch_size) + return spatial_features + + def _create_backbone_module(self, model: torch.nn.Module) -> torch.nn.Module: + return CenterPointHeadONNX(model.pts_backbone, model.pts_neck, model.pts_bbox_head) + + def _get_output_names(self, model: torch.nn.Module) -> Tuple[str, ...]: + if hasattr(model, "pts_bbox_head") and hasattr(model.pts_bbox_head, "output_names"): + output_names = model.pts_bbox_head.output_names + if isinstance(output_names, (list, tuple)): + return tuple(output_names) + return (output_names,) + return model_io["head_output_names"] + + def extract_features(self, model: torch.nn.Module, data_loader: Any, sample_idx: int) -> Tuple[torch.Tensor, dict]: + if hasattr(model, "_extract_features"): + return model._extract_features(data_loader, sample_idx) + raise AttributeError( + "CenterPoint model must have _extract_features method for ONNX export. " + "Please ensure the model is built with ONNX compatibility." + ) diff --git a/deployment/projects/centerpoint/export/onnx_export_pipeline.py b/deployment/projects/centerpoint/export/onnx_export_pipeline.py new file mode 100644 index 000000000..6938336b7 --- /dev/null +++ b/deployment/projects/centerpoint/export/onnx_export_pipeline.py @@ -0,0 +1,128 @@ +""" +CenterPoint ONNX export pipeline using composition. + +Moved from deployment/exporters/centerpoint/onnx_export_pipeline.py into the CenterPoint deployment bundle. +""" + +from __future__ import annotations + +import logging +import os +from pathlib import Path +from typing import Iterable, Optional, Tuple + +import torch + +from deployment.core import Artifact, BaseDataLoader, BaseDeploymentConfig +from deployment.exporters.common.factory import ExporterFactory +from deployment.exporters.common.model_wrappers import IdentityWrapper +from deployment.exporters.export_pipelines.base import OnnxExportPipeline +from deployment.exporters.export_pipelines.interfaces import ExportableComponent, ModelComponentExtractor + + +class CenterPointONNXExportPipeline(OnnxExportPipeline): + """ONNX export pipeline for CenterPoint (multi-file export). + + Uses a `ModelComponentExtractor` to split the model into exportable components + and exports each with the configured ONNX exporter. + """ + + def __init__( + self, + exporter_factory: type[ExporterFactory], + component_extractor: ModelComponentExtractor, + config: BaseDeploymentConfig, + logger: Optional[logging.Logger] = None, + ): + self.exporter_factory = exporter_factory + self.component_extractor = component_extractor + self.config = config + self.logger = logger or logging.getLogger(__name__) + + def export( + self, + *, + model: torch.nn.Module, + data_loader: BaseDataLoader, + output_dir: str, + config: BaseDeploymentConfig, + sample_idx: int = 0, + ) -> Artifact: + output_dir_path = Path(output_dir) + output_dir_path.mkdir(parents=True, exist_ok=True) + + self._log_header(output_dir_path, sample_idx) + sample_data = self._extract_sample_data(model, data_loader, sample_idx) + components = self.component_extractor.extract_components(model, sample_data) + + exported_paths = self._export_components(components, output_dir_path) + self._log_summary(exported_paths) + + return Artifact(path=str(output_dir_path), multi_file=True) + + def _log_header(self, output_dir: Path, sample_idx: int) -> None: + self.logger.info("=" * 80) + self.logger.info("Exporting CenterPoint to ONNX (multi-file)") + self.logger.info("=" * 80) + self.logger.info(f"Output directory: {output_dir}") + self.logger.info(f"Using sample index: {sample_idx}") + + def _extract_sample_data( + self, + model: torch.nn.Module, + data_loader: BaseDataLoader, + sample_idx: int, + ) -> Tuple[torch.Tensor, dict]: + if not hasattr(self.component_extractor, "extract_features"): + raise AttributeError("Component extractor must provide extract_features method") + + self.logger.info("Extracting features from sample data...") + try: + return self.component_extractor.extract_features(model, data_loader, sample_idx) + except Exception as exc: + self.logger.error("Failed to extract features", exc_info=exc) + raise RuntimeError("Feature extraction failed") from exc + + def _export_components( + self, + components: Iterable[ExportableComponent], + output_dir: Path, + ) -> Tuple[str, ...]: + exported_paths: list[str] = [] + component_list = list(components) + total = len(component_list) + + for index, component in enumerate(component_list, start=1): + self.logger.info(f"\n[{index}/{total}] Exporting {component.name}...") + exporter = self._build_onnx_exporter() + output_path = output_dir / f"{component.name}.onnx" + + try: + exporter.export( + model=component.module, + sample_input=component.sample_input, + output_path=str(output_path), + config_override=component.config_override, + ) + except Exception as exc: + self.logger.error(f"Failed to export {component.name}", exc_info=exc) + raise RuntimeError(f"{component.name} export failed") from exc + + exported_paths.append(str(output_path)) + self.logger.info(f"Exported {component.name}: {output_path}") + + return tuple(exported_paths) + + def _build_onnx_exporter(self): + return self.exporter_factory.create_onnx_exporter( + config=self.config, + wrapper_cls=IdentityWrapper, + logger=self.logger, + ) + + def _log_summary(self, exported_paths: Tuple[str, ...]) -> None: + self.logger.info("\n" + "=" * 80) + self.logger.info("CenterPoint ONNX export successful") + self.logger.info("=" * 80) + for path in exported_paths: + self.logger.info(f" • {os.path.basename(path)}") diff --git a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py new file mode 100644 index 000000000..d390371b0 --- /dev/null +++ b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py @@ -0,0 +1,103 @@ +""" +CenterPoint TensorRT export pipeline using composition. + +Moved from deployment/exporters/centerpoint/tensorrt_export_pipeline.py into the CenterPoint deployment bundle. +""" + +from __future__ import annotations + +import logging +import re +from pathlib import Path +from typing import List, Optional + +import torch + +from deployment.core import Artifact, BaseDataLoader, BaseDeploymentConfig +from deployment.exporters.common.factory import ExporterFactory +from deployment.exporters.export_pipelines.base import TensorRTExportPipeline + + +class CenterPointTensorRTExportPipeline(TensorRTExportPipeline): + """TensorRT export pipeline for CenterPoint. + + Consumes a directory of ONNX files (multi-file export) and builds a TensorRT + engine per component into `output_dir`. + """ + + _CUDA_DEVICE_PATTERN = re.compile(r"^cuda:\d+$") + + def __init__( + self, + exporter_factory: type[ExporterFactory], + config: BaseDeploymentConfig, + logger: Optional[logging.Logger] = None, + ): + self.exporter_factory = exporter_factory + self.config = config + self.logger = logger or logging.getLogger(__name__) + + def _validate_cuda_device(self, device: str) -> int: + if not self._CUDA_DEVICE_PATTERN.match(device): + raise ValueError( + f"Invalid CUDA device format: '{device}'. Expected format: 'cuda:N' (e.g., 'cuda:0', 'cuda:1')" + ) + return int(device.split(":")[1]) + + def export( + self, + *, + onnx_path: str, + output_dir: str, + config: BaseDeploymentConfig, + device: str, + data_loader: BaseDataLoader, + ) -> Artifact: + onnx_dir = onnx_path + + if device is None: + raise ValueError("CUDA device must be provided for TensorRT export") + if onnx_dir is None: + raise ValueError("onnx_dir must be provided for CenterPoint TensorRT export") + + onnx_dir_path = Path(onnx_dir) + if not onnx_dir_path.is_dir(): + raise ValueError(f"onnx_path must be a directory for multi-file export, got: {onnx_dir}") + + device_id = self._validate_cuda_device(device) + torch.cuda.set_device(device_id) + self.logger.info(f"Using CUDA device: {device}") + + output_dir_path = Path(output_dir) + output_dir_path.mkdir(parents=True, exist_ok=True) + + onnx_files = self._discover_onnx_files(onnx_dir_path) + if not onnx_files: + raise FileNotFoundError(f"No ONNX files found in {onnx_dir_path}") + + num_files = len(onnx_files) + for i, onnx_file in enumerate(onnx_files, 1): + trt_path = output_dir_path / f"{onnx_file.stem}.engine" + + self.logger.info(f"\n[{i}/{num_files}] Converting {onnx_file.name} → {trt_path.name}...") + exporter = self._build_tensorrt_exporter() + + artifact = exporter.export( + model=None, + sample_input=None, + output_path=str(trt_path), + onnx_path=str(onnx_file), + ) + self.logger.info(f"TensorRT engine saved: {artifact.path}") + + self.logger.info(f"\nAll TensorRT engines exported successfully to {output_dir_path}") + return Artifact(path=str(output_dir_path), multi_file=True) + + def _discover_onnx_files(self, onnx_dir: Path) -> List[Path]: + return sorted( + (path for path in onnx_dir.iterdir() if path.is_file() and path.suffix.lower() == ".onnx"), + key=lambda p: p.name, + ) + + def _build_tensorrt_exporter(self): + return self.exporter_factory.create_tensorrt_exporter(config=self.config, logger=self.logger) diff --git a/deployment/projects/centerpoint/model_loader.py b/deployment/projects/centerpoint/model_loader.py new file mode 100644 index 000000000..f48558e63 --- /dev/null +++ b/deployment/projects/centerpoint/model_loader.py @@ -0,0 +1,144 @@ +""" +CenterPoint deployment utilities: ONNX-compatible model building and metrics config extraction. + +Moved from projects/CenterPoint/deploy/utils.py into the unified deployment bundle. +""" + +import copy +import logging +from typing import List, Optional, Tuple + +import torch +from mmengine.config import Config +from mmengine.registry import MODELS, init_default_scope +from mmengine.runner import load_checkpoint + +from deployment.core.metrics.detection_3d_metrics import Detection3DMetricsConfig +from deployment.projects.centerpoint.onnx_models import register_models + + +def create_onnx_model_cfg( + model_cfg: Config, + device: str, + rot_y_axis_reference: bool = False, +) -> Config: + """Create a model config that swaps modules to ONNX-friendly variants. + + This mutates the `model_cfg.model` subtree to reference classes registered by + `deployment.projects.centerpoint.onnx_models` (e.g., `CenterPointONNX`). + """ + onnx_cfg = model_cfg.copy() + model_config = copy.deepcopy(onnx_cfg.model) + + model_config.type = "CenterPointONNX" + model_config.point_channels = model_config.pts_voxel_encoder.in_channels + model_config.device = device + + if model_config.pts_voxel_encoder.type == "PillarFeatureNet": + model_config.pts_voxel_encoder.type = "PillarFeatureNetONNX" + elif model_config.pts_voxel_encoder.type == "BackwardPillarFeatureNet": + model_config.pts_voxel_encoder.type = "BackwardPillarFeatureNetONNX" + + model_config.pts_bbox_head.type = "CenterHeadONNX" + model_config.pts_bbox_head.separate_head.type = "SeparateHeadONNX" + model_config.pts_bbox_head.rot_y_axis_reference = rot_y_axis_reference + + if ( + getattr(model_config, "pts_backbone", None) + and getattr(model_config.pts_backbone, "type", None) == "ConvNeXt_PC" + ): + model_config.pts_backbone.with_cp = False + + onnx_cfg.model = model_config + return onnx_cfg + + +def build_model_from_cfg(model_cfg: Config, checkpoint_path: str, device: str) -> torch.nn.Module: + """Build a model from MMEngine config and load checkpoint weights.""" + # Ensure CenterPoint ONNX variants are registered into MODELS before building. + # This is required because the config uses string types like "CenterPointONNX", "CenterHeadONNX", etc. + register_models() + init_default_scope("mmdet3d") + model_config = copy.deepcopy(model_cfg.model) + model = MODELS.build(model_config) + model.to(device) + load_checkpoint(model, checkpoint_path, map_location=device) + model.eval() + model.cfg = model_cfg + return model + + +def build_centerpoint_onnx_model( + base_model_cfg: Config, + checkpoint_path: str, + device: str, + rot_y_axis_reference: bool = False, +) -> Tuple[torch.nn.Module, Config]: + """Convenience wrapper to build an ONNX-compatible CenterPoint model + cfg.""" + onnx_cfg = create_onnx_model_cfg( + base_model_cfg, + device=device, + rot_y_axis_reference=rot_y_axis_reference, + ) + model = build_model_from_cfg(onnx_cfg, checkpoint_path, device=device) + return model, onnx_cfg + + +def extract_t4metric_v2_config( + model_cfg: Config, + class_names: Optional[List[str]] = None, + logger: Optional[logging.Logger] = None, +) -> Detection3DMetricsConfig: + """Extract `Detection3DMetricsConfig` from an MMEngine model config. + + Expects the config to contain a `T4MetricV2` evaluator (val or test). + """ + if logger is None: + logger = logging.getLogger(__name__) + + if class_names is None: + if hasattr(model_cfg, "class_names"): + class_names = model_cfg.class_names + else: + raise ValueError("class_names must be provided or defined in model_cfg.class_names") + + evaluator_cfg = None + if hasattr(model_cfg, "val_evaluator"): + evaluator_cfg = model_cfg.val_evaluator + elif hasattr(model_cfg, "test_evaluator"): + evaluator_cfg = model_cfg.test_evaluator + else: + raise ValueError("No val_evaluator or test_evaluator found in model_cfg") + + def get_cfg_value(cfg, key, default=None): + if cfg is None: + return default + if isinstance(cfg, dict): + return cfg.get(key, default) + return getattr(cfg, key, default) + + evaluator_type = get_cfg_value(evaluator_cfg, "type") + if evaluator_type != "T4MetricV2": + raise ValueError(f"Evaluator type is '{evaluator_type}', not 'T4MetricV2'") + + perception_configs = get_cfg_value(evaluator_cfg, "perception_evaluator_configs", {}) + evaluation_config_dict = get_cfg_value(perception_configs, "evaluation_config_dict") + frame_id = get_cfg_value(perception_configs, "frame_id", "base_link") + + critical_object_filter_config = get_cfg_value(evaluator_cfg, "critical_object_filter_config") + frame_pass_fail_config = get_cfg_value(evaluator_cfg, "frame_pass_fail_config") + + if evaluation_config_dict and hasattr(evaluation_config_dict, "to_dict"): + evaluation_config_dict = dict(evaluation_config_dict) + if critical_object_filter_config and hasattr(critical_object_filter_config, "to_dict"): + critical_object_filter_config = dict(critical_object_filter_config) + if frame_pass_fail_config and hasattr(frame_pass_fail_config, "to_dict"): + frame_pass_fail_config = dict(frame_pass_fail_config) + + return Detection3DMetricsConfig( + class_names=class_names, + frame_id=frame_id, + evaluation_config_dict=evaluation_config_dict, + critical_object_filter_config=critical_object_filter_config, + frame_pass_fail_config=frame_pass_fail_config, + ) diff --git a/deployment/projects/centerpoint/onnx_models/__init__.py b/deployment/projects/centerpoint/onnx_models/__init__.py new file mode 100644 index 000000000..94e04a288 --- /dev/null +++ b/deployment/projects/centerpoint/onnx_models/__init__.py @@ -0,0 +1,28 @@ +"""CenterPoint deploy-only ONNX model definitions. + +These modules exist to support ONNX export / ONNX-friendly execution graphs. +They are registered into MMEngine's `MODELS` registry via import side-effects +(`@MODELS.register_module()`). + +Important: +- Call `register_models()` before building models that reference types like + "CenterPointONNX", "CenterHeadONNX", "SeparateHeadONNX", + "PillarFeatureNetONNX", "BackwardPillarFeatureNetONNX". +""" + +from __future__ import annotations + + +def register_models() -> None: + """Register CenterPoint ONNX model variants into MMEngine's `MODELS` registry. + + The underlying modules use `@MODELS.register_module()`; importing them is enough + to register the types referenced by config strings (e.g., `CenterPointONNX`). + """ + # Importing modules triggers `@MODELS.register_module()` registrations. + from deployment.projects.centerpoint.onnx_models import centerpoint_head_onnx as _ # noqa: F401 + from deployment.projects.centerpoint.onnx_models import centerpoint_onnx as _ # noqa: F401 + from deployment.projects.centerpoint.onnx_models import pillar_encoder_onnx as _ # noqa: F401 + + +__all__ = ["register_models"] diff --git a/projects/CenterPoint/models/dense_heads/centerpoint_head_onnx.py b/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py similarity index 95% rename from projects/CenterPoint/models/dense_heads/centerpoint_head_onnx.py rename to deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py index c12df19cd..ee2a85491 100644 --- a/projects/CenterPoint/models/dense_heads/centerpoint_head_onnx.py +++ b/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py @@ -1,3 +1,9 @@ +"""CenterPoint deploy-only ONNX head variants. + +These heads adjust output ordering and forward behavior to improve ONNX export +and downstream inference compatibility. +""" + from typing import Dict, List, Tuple import torch @@ -5,7 +11,7 @@ from mmdet3d.registry import MODELS from mmengine.logging import MMLogger -from .centerpoint_head import CenterHead +from projects.CenterPoint.models.dense_heads.centerpoint_head import CenterHead @MODELS.register_module() diff --git a/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py b/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py new file mode 100644 index 000000000..ec83124d6 --- /dev/null +++ b/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py @@ -0,0 +1,147 @@ +"""CenterPoint deploy-only ONNX model variants. + +These modules provide ONNX-friendly model wrappers and detector variants used by +the deployment/export pipeline (not training). +""" + +import os +from typing import Dict, List, Tuple + +import numpy as np +import torch +from mmdet3d.models.detectors.centerpoint import CenterPoint +from mmdet3d.registry import MODELS +from mmengine.logging import MMLogger +from torch import nn + + +class CenterPointHeadONNX(nn.Module): + """Head module for centerpoint with BACKBONE, NECK and BBOX_HEAD""" + + def __init__(self, backbone: nn.Module, neck: nn.Module, bbox_head: nn.Module): + super(CenterPointHeadONNX, self).__init__() + self.backbone: nn.Module = backbone + self.neck: nn.Module = neck + self.bbox_head: nn.Module = bbox_head + self._logger = MMLogger.get_current_instance() + self._logger.info("Running CenterPointHeadONNX!") + + def forward(self, x: torch.Tensor) -> Tuple[List[Dict[str, torch.Tensor]]]: + """ + Note: + torch.onnx.export() doesn't support triple-nested output + + Args: + x (torch.Tensor): (B, C, H, W) + Returns: + tuple[list[dict[str, any]]]: + (num_classes x [num_detect x {'reg', 'height', 'dim', 'rot', 'vel', 'heatmap'}]) + """ + x = self.backbone(x) + if self.neck is not None: + x = self.neck(x) + x = self.bbox_head(x) + + return x + + +@MODELS.register_module() +class CenterPointONNX(CenterPoint): + """onnx support impl of mmdet3d.models.detectors.CenterPoint""" + + def __init__(self, point_channels: int = 5, device: str = "cpu", **kwargs): + super().__init__(**kwargs) + self._point_channels = point_channels + self._device = device + # Handle both "cuda:0" and "gpu" device strings + if self._device.startswith("cuda") or self._device == "gpu": + self._torch_device = torch.device(self._device if self._device.startswith("cuda") else "cuda:0") + else: + self._torch_device = torch.device("cpu") + self._logger = MMLogger.get_current_instance() + self._logger.info("Running CenterPointONNX!") + + def _get_inputs(self, data_loader, sample_idx=0): + """ + Generate inputs from the provided data loader. + + Args: + data_loader: Loader that implements ``load_sample``. + sample_idx: Index of the sample to fetch. + """ + if data_loader is None: + raise ValueError("data_loader is required for CenterPoint ONNX export") + + if not hasattr(data_loader, "load_sample"): + raise AttributeError("data_loader must implement 'load_sample(sample_idx)'") + + sample = data_loader.load_sample(sample_idx) + + if "lidar_points" not in sample: + raise KeyError("Sample does not contain 'lidar_points'") + + lidar_path = sample["lidar_points"].get("lidar_path") + if not lidar_path: + raise ValueError("Sample must provide 'lidar_path' inside 'lidar_points'") + + if not os.path.exists(lidar_path): + raise FileNotFoundError(f"Lidar path not found: {lidar_path}") + + points = self._load_point_cloud(lidar_path) + points = torch.from_numpy(points).to(self._torch_device) + points = [points] + return {"points": points, "data_samples": None} + + def _load_point_cloud(self, lidar_path: str) -> np.ndarray: + """ + Load point cloud from file. + + Args: + lidar_path: Path to point cloud file (.bin or .pcd) + + Returns: + Point cloud array (N, 5) where 5 = (x, y, z, intensity, ring_id) + """ + if lidar_path.endswith(".bin"): + # Load binary point cloud (KITTI/nuScenes format) + # T4 dataset has 5 features: x, y, z, intensity, ring_id + points = np.fromfile(lidar_path, dtype=np.float32).reshape(-1, 5) + + # Don't pad here - let the voxelization process handle feature expansion + # The voxelization process will add cluster_center (+3) and voxel_center (+3) features + # So 5 + 3 + 3 = 11 features total + + elif lidar_path.endswith(".pcd"): + # Load PCD format (placeholder - would need pypcd or similar) + raise NotImplementedError("PCD format loading not implemented yet") + else: + raise ValueError(f"Unsupported point cloud format: {lidar_path}") + + return points + + def _extract_features(self, data_loader, sample_idx=0): + """ + Extract features using samples from the provided data loader. + """ + if data_loader is None: + raise ValueError("data_loader is required to extract features") + + assert self.data_preprocessor is not None and hasattr(self.data_preprocessor, "voxelize") + + # Ensure data preprocessor is on the correct device + if hasattr(self.data_preprocessor, "to"): + self.data_preprocessor.to(self._torch_device) + + inputs = self._get_inputs(data_loader, sample_idx) + voxel_dict = self.data_preprocessor.voxelize(points=inputs["points"], data_samples=inputs["data_samples"]) + + # Ensure all voxel tensors are on the correct device + for key in ["voxels", "num_points", "coors"]: + if key in voxel_dict and isinstance(voxel_dict[key], torch.Tensor): + voxel_dict[key] = voxel_dict[key].to(self._torch_device) + + assert self.pts_voxel_encoder is not None and hasattr(self.pts_voxel_encoder, "get_input_features") + input_features = self.pts_voxel_encoder.get_input_features( + voxel_dict["voxels"], voxel_dict["num_points"], voxel_dict["coors"] + ) + return input_features, voxel_dict diff --git a/projects/CenterPoint/models/voxel_encoders/pillar_encoder_onnx.py b/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py similarity index 96% rename from projects/CenterPoint/models/voxel_encoders/pillar_encoder_onnx.py rename to deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py index 73ab10d90..45f81bbde 100644 --- a/projects/CenterPoint/models/voxel_encoders/pillar_encoder_onnx.py +++ b/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py @@ -1,3 +1,9 @@ +"""CenterPoint deploy-only ONNX voxel encoder variants. + +These variants expose helper APIs and forward shapes that are friendlier for ONNX export +and componentized inference pipelines. +""" + from typing import Optional import torch @@ -7,7 +13,7 @@ from mmengine.logging import MMLogger from torch import Tensor -from .pillar_encoder import BackwardPillarFeatureNet +from projects.CenterPoint.models.voxel_encoders.pillar_encoder import BackwardPillarFeatureNet @MODELS.register_module() diff --git a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py new file mode 100644 index 000000000..31015d625 --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py @@ -0,0 +1,157 @@ +""" +CenterPoint Deployment Pipeline Base Class. + +Moved from deployment/pipelines/centerpoint/centerpoint_pipeline.py into the CenterPoint deployment bundle. +""" + +import logging +import time +from abc import abstractmethod +from typing import Dict, List, Tuple + +import torch +from mmdet3d.structures import Det3DDataSample, LiDARInstance3DBoxes + +from deployment.pipelines.base_pipeline import BaseDeploymentPipeline + +logger = logging.getLogger(__name__) + + +class CenterPointDeploymentPipeline(BaseDeploymentPipeline): + """Base pipeline for CenterPoint staged inference. + + This normalizes preprocessing/postprocessing for CenterPoint and provides + common helpers (e.g., middle encoder processing) used by PyTorch/ONNX/TensorRT + backend-specific pipelines. + """ + + def __init__(self, pytorch_model, device: str = "cuda", backend_type: str = "unknown"): + cfg = getattr(pytorch_model, "cfg", None) + + class_names = getattr(cfg, "class_names", None) + if class_names is None: + raise ValueError("class_names not found in pytorch_model.cfg") + + point_cloud_range = getattr(cfg, "point_cloud_range", None) + voxel_size = getattr(cfg, "voxel_size", None) + + super().__init__( + model=pytorch_model, + device=device, + task_type="detection3d", + backend_type=backend_type, + ) + + self.num_classes = len(class_names) + self.class_names = class_names + self.point_cloud_range = point_cloud_range + self.voxel_size = voxel_size + self.pytorch_model = pytorch_model + self._stage_latencies = {} + + def preprocess(self, points: torch.Tensor, **kwargs) -> Tuple[Dict[str, torch.Tensor], Dict]: + points_tensor = points.to(self.device) + + data_samples = [Det3DDataSample()] + with torch.no_grad(): + batch_inputs = self.pytorch_model.data_preprocessor( + {"inputs": {"points": [points_tensor]}, "data_samples": data_samples} + ) + + voxel_dict = batch_inputs["inputs"]["voxels"] + voxels = voxel_dict["voxels"] + num_points = voxel_dict["num_points"] + coors = voxel_dict["coors"] + + input_features = None + with torch.no_grad(): + if hasattr(self.pytorch_model.pts_voxel_encoder, "get_input_features"): + input_features = self.pytorch_model.pts_voxel_encoder.get_input_features(voxels, num_points, coors) + + preprocessed_dict = { + "input_features": input_features, + "voxels": voxels, + "num_points": num_points, + "coors": coors, + } + + return preprocessed_dict, {} + + def process_middle_encoder(self, voxel_features: torch.Tensor, coors: torch.Tensor) -> torch.Tensor: + voxel_features = voxel_features.to(self.device) + coors = coors.to(self.device) + batch_size = int(coors[-1, 0].item()) + 1 if len(coors) > 0 else 1 + with torch.no_grad(): + spatial_features = self.pytorch_model.pts_middle_encoder(voxel_features, coors, batch_size) + return spatial_features + + def postprocess(self, head_outputs: List[torch.Tensor], sample_meta: Dict) -> List[Dict]: + head_outputs = [out.to(self.device) for out in head_outputs] + if len(head_outputs) != 6: + raise ValueError(f"Expected 6 head outputs, got {len(head_outputs)}") + + heatmap, reg, height, dim, rot, vel = head_outputs + + if hasattr(self.pytorch_model, "pts_bbox_head"): + rot_y_axis_reference = getattr(self.pytorch_model.pts_bbox_head, "_rot_y_axis_reference", False) + if rot_y_axis_reference: + dim = dim[:, [1, 0, 2], :, :] + rot = rot * (-1.0) + rot = rot[:, [1, 0], :, :] + + preds_dict = {"heatmap": heatmap, "reg": reg, "height": height, "dim": dim, "rot": rot, "vel": vel} + preds_dicts = ([preds_dict],) + + if "box_type_3d" not in sample_meta: + sample_meta["box_type_3d"] = LiDARInstance3DBoxes + batch_input_metas = [sample_meta] + + with torch.no_grad(): + predictions_list = self.pytorch_model.pts_bbox_head.predict_by_feat( + preds_dicts=preds_dicts, batch_input_metas=batch_input_metas + ) + + results = [] + for pred_instances in predictions_list: + bboxes_3d = pred_instances.bboxes_3d.tensor.cpu().numpy() + scores_3d = pred_instances.scores_3d.cpu().numpy() + labels_3d = pred_instances.labels_3d.cpu().numpy() + + for i in range(len(bboxes_3d)): + results.append( + { + "bbox_3d": bboxes_3d[i][:7].tolist(), + "score": float(scores_3d[i]), + "label": int(labels_3d[i]), + } + ) + + return results + + @abstractmethod + def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + raise NotImplementedError + + @abstractmethod + def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + raise NotImplementedError + + def run_model(self, preprocessed_input: Dict[str, torch.Tensor]) -> Tuple[List[torch.Tensor], Dict[str, float]]: + stage_latencies = {} + + start = time.perf_counter() + voxel_features = self.run_voxel_encoder(preprocessed_input["input_features"]) + stage_latencies["voxel_encoder_ms"] = (time.perf_counter() - start) * 1000 + + start = time.perf_counter() + spatial_features = self.process_middle_encoder(voxel_features, preprocessed_input["coors"]) + stage_latencies["middle_encoder_ms"] = (time.perf_counter() - start) * 1000 + + start = time.perf_counter() + head_outputs = self.run_backbone_head(spatial_features) + stage_latencies["backbone_head_ms"] = (time.perf_counter() - start) * 1000 + + return head_outputs, stage_latencies + + def __repr__(self): + return f"{self.__class__.__name__}(device={self.device})" diff --git a/deployment/projects/centerpoint/pipelines/factory.py b/deployment/projects/centerpoint/pipelines/factory.py new file mode 100644 index 000000000..af3bfceab --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/factory.py @@ -0,0 +1,64 @@ +""" +CenterPoint Pipeline Factory. + +Registers CenterPoint pipelines into the global pipeline_registry so evaluators can create pipelines +via `deployment.pipelines.factory.PipelineFactory`. +""" + +import logging +from typing import Any, Optional + +from deployment.core.backend import Backend +from deployment.core.evaluation.evaluator_types import ModelSpec +from deployment.pipelines.base_factory import BasePipelineFactory +from deployment.pipelines.base_pipeline import BaseDeploymentPipeline +from deployment.pipelines.registry import pipeline_registry +from deployment.projects.centerpoint.pipelines.onnx import CenterPointONNXPipeline +from deployment.projects.centerpoint.pipelines.pytorch import CenterPointPyTorchPipeline +from deployment.projects.centerpoint.pipelines.tensorrt import CenterPointTensorRTPipeline + +logger = logging.getLogger(__name__) + + +@pipeline_registry.register +class CenterPointPipelineFactory(BasePipelineFactory): + """Pipeline factory for CenterPoint across supported backends.""" + + @classmethod + def get_project_name(cls) -> str: + return "centerpoint" + + @classmethod + def create_pipeline( + cls, + model_spec: ModelSpec, + pytorch_model: Any, + device: Optional[str] = None, + **kwargs, + ) -> BaseDeploymentPipeline: + device = device or model_spec.device + backend = model_spec.backend + + cls._validate_backend(backend) + + if backend is Backend.PYTORCH: + logger.info(f"Creating CenterPoint PyTorch pipeline on {device}") + return CenterPointPyTorchPipeline(pytorch_model, device=device) + + if backend is Backend.ONNX: + logger.info(f"Creating CenterPoint ONNX pipeline from {model_spec.path} on {device}") + return CenterPointONNXPipeline( + pytorch_model, + onnx_dir=model_spec.path, + device=device, + ) + + if backend is Backend.TENSORRT: + logger.info(f"Creating CenterPoint TensorRT pipeline from {model_spec.path} on {device}") + return CenterPointTensorRTPipeline( + pytorch_model, + tensorrt_dir=model_spec.path, + device=device, + ) + + raise ValueError(f"Unsupported backend: {backend.value}") diff --git a/deployment/projects/centerpoint/pipelines/onnx.py b/deployment/projects/centerpoint/pipelines/onnx.py new file mode 100644 index 000000000..f42713fbc --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/onnx.py @@ -0,0 +1,86 @@ +""" +CenterPoint ONNX Pipeline Implementation. + +Moved from deployment/pipelines/centerpoint/centerpoint_onnx.py into the CenterPoint deployment bundle. +""" + +import logging +import os.path as osp +from typing import List + +import numpy as np +import onnxruntime as ort +import torch + +from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline + +logger = logging.getLogger(__name__) + + +class CenterPointONNXPipeline(CenterPointDeploymentPipeline): + """ONNXRuntime-based CenterPoint pipeline (componentized inference).""" + + def __init__(self, pytorch_model, onnx_dir: str, device: str = "cpu"): + super().__init__(pytorch_model, device, backend_type="onnx") + + self.onnx_dir = onnx_dir + self._load_onnx_models(device) + logger.info(f"ONNX pipeline initialized with models from: {onnx_dir}") + + def _load_onnx_models(self, device: str): + voxel_encoder_path = osp.join(self.onnx_dir, "pts_voxel_encoder.onnx") + backbone_head_path = osp.join(self.onnx_dir, "pts_backbone_neck_head.onnx") + + if not osp.exists(voxel_encoder_path): + raise FileNotFoundError(f"Voxel encoder ONNX not found: {voxel_encoder_path}") + if not osp.exists(backbone_head_path): + raise FileNotFoundError(f"Backbone head ONNX not found: {backbone_head_path}") + + so = ort.SessionOptions() + so.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL + so.log_severity_level = 3 + + if device.startswith("cuda"): + providers = ["CUDAExecutionProvider", "CPUExecutionProvider"] + logger.info("Using CUDA execution provider for ONNX") + else: + providers = ["CPUExecutionProvider"] + logger.info("Using CPU execution provider for ONNX") + + try: + self.voxel_encoder_session = ort.InferenceSession(voxel_encoder_path, sess_options=so, providers=providers) + logger.info(f"Loaded voxel encoder: {voxel_encoder_path}") + except Exception as e: + raise RuntimeError(f"Failed to load voxel encoder ONNX: {e}") + + try: + self.backbone_head_session = ort.InferenceSession(backbone_head_path, sess_options=so, providers=providers) + logger.info(f"Loaded backbone+head: {backbone_head_path}") + except Exception as e: + raise RuntimeError(f"Failed to load backbone+head ONNX: {e}") + + def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + input_array = input_features.cpu().numpy().astype(np.float32) + input_name = self.voxel_encoder_session.get_inputs()[0].name + output_name = self.voxel_encoder_session.get_outputs()[0].name + + outputs = self.voxel_encoder_session.run([output_name], {input_name: input_array}) + + voxel_features = torch.from_numpy(outputs[0]).to(self.device) + if voxel_features.ndim == 3 and voxel_features.shape[1] == 1: + voxel_features = voxel_features.squeeze(1) + return voxel_features + + def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + input_array = spatial_features.cpu().numpy().astype(np.float32) + + input_name = self.backbone_head_session.get_inputs()[0].name + output_names = [output.name for output in self.backbone_head_session.get_outputs()] + + outputs = self.backbone_head_session.run(output_names, {input_name: input_array}) + head_outputs = [torch.from_numpy(out).to(self.device) for out in outputs] + + if len(head_outputs) != 6: + raise ValueError(f"Expected 6 head outputs, got {len(head_outputs)}") + + return head_outputs diff --git a/deployment/projects/centerpoint/pipelines/pytorch.py b/deployment/projects/centerpoint/pipelines/pytorch.py new file mode 100644 index 000000000..3f43aab55 --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/pytorch.py @@ -0,0 +1,87 @@ +""" +CenterPoint PyTorch Pipeline Implementation. + +Moved from deployment/pipelines/centerpoint/centerpoint_pytorch.py into the CenterPoint deployment bundle. +""" + +import logging +from typing import Dict, List + +import torch + +from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline + +logger = logging.getLogger(__name__) + + +class CenterPointPyTorchPipeline(CenterPointDeploymentPipeline): + """PyTorch-based CenterPoint pipeline (staged to match ONNX/TensorRT outputs).""" + + def __init__(self, pytorch_model, device: str = "cuda"): + super().__init__(pytorch_model, device, backend_type="pytorch") + logger.info("PyTorch pipeline initialized (ONNX-compatible staged inference)") + + def infer(self, points: torch.Tensor, sample_meta: Dict = None, return_raw_outputs: bool = False): + if sample_meta is None: + sample_meta = {} + return super().infer(points, sample_meta, return_raw_outputs=return_raw_outputs) + + def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + if input_features is None: + raise ValueError("input_features is None. This should not happen for ONNX models.") + + input_features = input_features.to(self.device) + + with torch.no_grad(): + voxel_features = self.pytorch_model.pts_voxel_encoder(input_features) + + if voxel_features.ndim == 3: + if voxel_features.shape[1] == 1: + voxel_features = voxel_features.squeeze(1) + elif voxel_features.shape[2] == 1: + voxel_features = voxel_features.squeeze(2) + else: + raise RuntimeError( + f"Voxel encoder output has unexpected 3D shape: {voxel_features.shape}. " + f"Expected 2D output [N_voxels, feature_dim]. Input was: {input_features.shape}" + ) + elif voxel_features.ndim > 3: + raise RuntimeError( + f"Voxel encoder output has {voxel_features.ndim}D shape: {voxel_features.shape}. " + "Expected 2D output [N_voxels, feature_dim]." + ) + + return voxel_features + + def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + spatial_features = spatial_features.to(self.device) + + with torch.no_grad(): + x = self.pytorch_model.pts_backbone(spatial_features) + + if hasattr(self.pytorch_model, "pts_neck") and self.pytorch_model.pts_neck is not None: + x = self.pytorch_model.pts_neck(x) + + head_outputs_tuple = self.pytorch_model.pts_bbox_head(x) + + if isinstance(head_outputs_tuple, tuple) and len(head_outputs_tuple) > 0: + first_element = head_outputs_tuple[0] + + if isinstance(first_element, torch.Tensor): + head_outputs = list(head_outputs_tuple) + elif isinstance(first_element, list) and len(first_element) > 0: + preds_dict = first_element[0] + head_outputs = [ + preds_dict["heatmap"], + preds_dict["reg"], + preds_dict["height"], + preds_dict["dim"], + preds_dict["rot"], + preds_dict["vel"], + ] + else: + raise ValueError(f"Unexpected task_outputs format: {type(first_element)}") + else: + raise ValueError(f"Unexpected head_outputs format: {type(head_outputs_tuple)}") + + return head_outputs diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py new file mode 100644 index 000000000..525c2bbd1 --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -0,0 +1,178 @@ +""" +CenterPoint TensorRT Pipeline Implementation. + +Moved from deployment/pipelines/centerpoint/centerpoint_tensorrt.py into the CenterPoint deployment bundle. +""" + +import logging +import os.path as osp +from typing import List + +import numpy as np +import pycuda.autoinit # noqa: F401 +import pycuda.driver as cuda +import tensorrt as trt +import torch + +from deployment.pipelines.gpu_resource_mixin import ( + GPUResourceMixin, + TensorRTResourceManager, + release_tensorrt_resources, +) +from deployment.projects.centerpoint.config.deploy_config import onnx_config +from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline + +logger = logging.getLogger(__name__) + + +class CenterPointTensorRTPipeline(GPUResourceMixin, CenterPointDeploymentPipeline): + """TensorRT-based CenterPoint pipeline (engine-per-component inference).""" + + def __init__(self, pytorch_model, tensorrt_dir: str, device: str = "cuda"): + if not device.startswith("cuda"): + raise ValueError("TensorRT requires CUDA device") + + super().__init__(pytorch_model, device, backend_type="tensorrt") + + self.tensorrt_dir = tensorrt_dir + self._engines = {} + self._contexts = {} + self._logger = trt.Logger(trt.Logger.WARNING) + self._cleanup_called = False + + self._load_tensorrt_engines() + logger.info(f"TensorRT pipeline initialized with engines from: {tensorrt_dir}") + + def _load_tensorrt_engines(self): + trt.init_libnvinfer_plugins(self._logger, "") + runtime = trt.Runtime(self._logger) + + component_cfg = onnx_config.get("components", {}) + voxel_cfg = component_cfg.get("voxel_encoder", {}) + backbone_cfg = component_cfg.get("backbone_head", {}) + engine_files = { + "voxel_encoder": voxel_cfg.get("engine_file", "pts_voxel_encoder.engine"), + "backbone_neck_head": backbone_cfg.get("engine_file", "pts_backbone_neck_head.engine"), + } + + for component, engine_file in engine_files.items(): + engine_path = osp.join(self.tensorrt_dir, engine_file) + if not osp.exists(engine_path): + raise FileNotFoundError(f"TensorRT engine not found: {engine_path}") + + with open(engine_path, "rb") as f: + engine = runtime.deserialize_cuda_engine(f.read()) + if engine is None: + raise RuntimeError(f"Failed to deserialize engine: {engine_path}") + + context = engine.create_execution_context() + if context is None: + raise RuntimeError( + f"Failed to create execution context for {component}. " "This is likely due to GPU out-of-memory." + ) + + self._engines[component] = engine + self._contexts[component] = context + logger.info(f"Loaded TensorRT engine: {component}") + + def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + engine = self._engines["voxel_encoder"] + context = self._contexts["voxel_encoder"] + if context is None: + raise RuntimeError("voxel_encoder context is None - likely failed to initialize due to GPU OOM") + + input_array = input_features.cpu().numpy().astype(np.float32) + if not input_array.flags["C_CONTIGUOUS"]: + input_array = np.ascontiguousarray(input_array) + + input_name, output_name = self._get_io_names(engine, single_output=True) + context.set_input_shape(input_name, input_array.shape) + output_shape = context.get_tensor_shape(output_name) + output_array = np.empty(output_shape, dtype=np.float32) + if not output_array.flags["C_CONTIGUOUS"]: + output_array = np.ascontiguousarray(output_array) + + with TensorRTResourceManager() as manager: + d_input = manager.allocate(input_array.nbytes) + d_output = manager.allocate(output_array.nbytes) + stream = manager.get_stream() + + context.set_tensor_address(input_name, int(d_input)) + context.set_tensor_address(output_name, int(d_output)) + + cuda.memcpy_htod_async(d_input, input_array, stream) + context.execute_async_v3(stream_handle=stream.handle) + cuda.memcpy_dtoh_async(output_array, d_output, stream) + manager.synchronize() + + voxel_features = torch.from_numpy(output_array).to(self.device) + voxel_features = voxel_features.squeeze(1) + return voxel_features + + def _get_io_names(self, engine, single_output: bool = False): + input_name = None + output_names = [] + + for i in range(engine.num_io_tensors): + tensor_name = engine.get_tensor_name(i) + if engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.INPUT: + input_name = tensor_name + elif engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.OUTPUT: + output_names.append(tensor_name) + + if input_name is None: + raise RuntimeError("Could not find input tensor name") + if not output_names: + raise RuntimeError("Could not find output tensor names") + + if single_output: + return input_name, output_names[0] + return input_name, output_names + + def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + engine = self._engines["backbone_neck_head"] + context = self._contexts["backbone_neck_head"] + if context is None: + raise RuntimeError("backbone_neck_head context is None - likely failed to initialize due to GPU OOM") + + input_array = spatial_features.cpu().numpy().astype(np.float32) + if not input_array.flags["C_CONTIGUOUS"]: + input_array = np.ascontiguousarray(input_array) + + input_name, output_names = self._get_io_names(engine, single_output=False) + context.set_input_shape(input_name, input_array.shape) + + output_arrays = {} + for output_name in output_names: + output_shape = context.get_tensor_shape(output_name) + output_array = np.empty(output_shape, dtype=np.float32) + if not output_array.flags["C_CONTIGUOUS"]: + output_array = np.ascontiguousarray(output_array) + output_arrays[output_name] = output_array + + with TensorRTResourceManager() as manager: + d_input = manager.allocate(input_array.nbytes) + d_outputs = {name: manager.allocate(arr.nbytes) for name, arr in output_arrays.items()} + stream = manager.get_stream() + + context.set_tensor_address(input_name, int(d_input)) + for output_name in output_names: + context.set_tensor_address(output_name, int(d_outputs[output_name])) + + cuda.memcpy_htod_async(d_input, input_array, stream) + context.execute_async_v3(stream_handle=stream.handle) + + for output_name in output_names: + cuda.memcpy_dtoh_async(output_arrays[output_name], d_outputs[output_name], stream) + manager.synchronize() + + head_outputs = [torch.from_numpy(output_arrays[name]).to(self.device) for name in output_names] + if len(head_outputs) != 6: + raise ValueError(f"Expected 6 head outputs, got {len(head_outputs)}") + return head_outputs + + def _release_gpu_resources(self) -> None: + release_tensorrt_resources( + engines=getattr(self, "_engines", None), + contexts=getattr(self, "_contexts", None), + ) diff --git a/deployment/projects/centerpoint/runner.py b/deployment/projects/centerpoint/runner.py new file mode 100644 index 000000000..47e35338e --- /dev/null +++ b/deployment/projects/centerpoint/runner.py @@ -0,0 +1,99 @@ +""" +CenterPoint-specific deployment runner. + +Moved from deployment/runners/projects/centerpoint_runner.py into the unified deployment bundle. +""" + +from __future__ import annotations + +import logging +from typing import Any + +from deployment.core.contexts import CenterPointExportContext, ExportContext +from deployment.exporters.common.factory import ExporterFactory +from deployment.exporters.common.model_wrappers import IdentityWrapper +from deployment.projects.centerpoint.export.component_extractor import CenterPointComponentExtractor +from deployment.projects.centerpoint.export.onnx_export_pipeline import CenterPointONNXExportPipeline +from deployment.projects.centerpoint.export.tensorrt_export_pipeline import CenterPointTensorRTExportPipeline +from deployment.projects.centerpoint.model_loader import build_centerpoint_onnx_model +from deployment.runtime.runner import BaseDeploymentRunner + + +class CenterPointDeploymentRunner(BaseDeploymentRunner): + """CenterPoint deployment runner. + + Implements project-specific model loading and wiring to export pipelines, + while reusing the project-agnostic orchestration in `BaseDeploymentRunner`. + """ + + def __init__( + self, + data_loader, + evaluator, + config, + model_cfg, + logger: logging.Logger, + onnx_pipeline=None, + tensorrt_pipeline=None, + ): + simplify_onnx = config.get_onnx_settings().simplify + component_extractor = CenterPointComponentExtractor(logger=logger, simplify=simplify_onnx) + + super().__init__( + data_loader=data_loader, + evaluator=evaluator, + config=config, + model_cfg=model_cfg, + logger=logger, + onnx_wrapper_cls=IdentityWrapper, + onnx_pipeline=onnx_pipeline, + tensorrt_pipeline=tensorrt_pipeline, + ) + + if self._onnx_pipeline is None: + self._onnx_pipeline = CenterPointONNXExportPipeline( + exporter_factory=ExporterFactory, + component_extractor=component_extractor, + config=self.config, + logger=self.logger, + ) + + if self._tensorrt_pipeline is None: + self._tensorrt_pipeline = CenterPointTensorRTExportPipeline( + exporter_factory=ExporterFactory, + config=self.config, + logger=self.logger, + ) + + def load_pytorch_model(self, checkpoint_path: str, context: ExportContext) -> Any: + rot_y_axis_reference: bool = False + if isinstance(context, CenterPointExportContext): + rot_y_axis_reference = context.rot_y_axis_reference + else: + rot_y_axis_reference = context.get("rot_y_axis_reference", False) + + model, onnx_cfg = build_centerpoint_onnx_model( + base_model_cfg=self.model_cfg, + checkpoint_path=checkpoint_path, + device="cpu", + rot_y_axis_reference=rot_y_axis_reference, + ) + + self.model_cfg = onnx_cfg + self._inject_model_to_evaluator(model, onnx_cfg) + return model + + def _inject_model_to_evaluator(self, model: Any, onnx_cfg: Any) -> None: + try: + self.evaluator.set_onnx_config(onnx_cfg) + self.logger.info("Injected ONNX-compatible config to evaluator") + except Exception as e: + self.logger.error(f"Failed to inject ONNX config: {e}") + raise + + try: + self.evaluator.set_pytorch_model(model) + self.logger.info("Injected PyTorch model to evaluator") + except Exception as e: + self.logger.error(f"Failed to inject PyTorch model: {e}") + raise diff --git a/projects/CenterPoint/Dockerfile b/projects/CenterPoint/Dockerfile new file mode 100644 index 000000000..7b86c99eb --- /dev/null +++ b/projects/CenterPoint/Dockerfile @@ -0,0 +1,13 @@ +ARG AWML_BASE_IMAGE="autoware-ml:latest" +FROM ${AWML_BASE_IMAGE} +ARG TRT_VERSION=10.8.0.43 + +# Install pip dependencies +RUN python3 -m pip --no-cache-dir install \ + onnxruntime-gpu --extra-index-url https://aiinfra.pkgs.visualstudio.com/PublicPackages/_packaging/onnxruntime-cuda-12/pypi/simple/ \ + onnxsim \ + pycuda \ + tensorrt-cu12==${TRT_VERSION} + +WORKDIR /workspace +RUN pip install --no-cache-dir -e . diff --git a/projects/CenterPoint/README.md b/projects/CenterPoint/README.md index 6b265e890..cc26b910a 100644 --- a/projects/CenterPoint/README.md +++ b/projects/CenterPoint/README.md @@ -41,6 +41,11 @@ docker run -it --rm --gpus all --shm-size=64g --name awml -p 6006:6006 -v $PWD/:/workspace -v $PWD/data:/workspace/data autoware-ml ``` +For ONNX and TensorRT evaluation +```sh +docker run -it --rm --gpus all --shm-size=64g --name awml_deployment -p 6006:6006 -v $PWD/:/workspace -v $PWD/data:/workspace/data centerpoint-deployment:latest +``` + ### 2. Train #### 2.1 Environment set up @@ -110,12 +115,14 @@ where `frame-range` represents the range of frames to visualize. ### 5. Deploy -- Make an onnx file for a CenterPoint model. +- Run the unified deployment pipeline to export ONNX/TensorRT artifacts, verify them, and (optionally) evaluate. Update `deployment/projects/centerpoint/config/deploy_config.py` so that `checkpoint_path`, `runtime_io.info_file`, and `export.work_dir` point to your experiment (e.g., `checkpoint_path="work_dirs/centerpoint/t4dataset/second_secfpn_2xb8_121m_base/epoch_50.pth"`). ```sh -# Deploy for t4dataset -DIR="work_dirs/centerpoint/t4dataset/second_secfpn_2xb8_121m_base/" && -python projects/CenterPoint/scripts/deploy.py projects/CenterPoint/configs/t4dataset/second_secfpn_2xb8_121m_base.py $DIR/epoch_50.pth --replace_onnx_models --device gpu --rot_y_axis_reference +# Deploy for t4dataset (export + verification + evaluation) +python -m deployment.cli.main centerpoint \ + deployment/projects/centerpoint/config/deploy_config.py \ + projects/CenterPoint/configs/t4dataset/second_secfpn_2xb8_121m_base.py \ + --rot-y-axis-reference ``` where `rot_y_axis_reference` can be removed if we would like to use the original counterclockwise x-axis rotation system. diff --git a/projects/CenterPoint/models/__init__.py b/projects/CenterPoint/models/__init__.py index 13d1792cb..c713add79 100644 --- a/projects/CenterPoint/models/__init__.py +++ b/projects/CenterPoint/models/__init__.py @@ -1,13 +1,10 @@ from .backbones.second import SECOND from .dense_heads.centerpoint_head import CenterHead, CustomSeparateHead -from .dense_heads.centerpoint_head_onnx import CenterHeadONNX, SeparateHeadONNX from .detectors.centerpoint import CenterPoint -from .detectors.centerpoint_onnx import CenterPointONNX from .losses.amp_gaussian_focal_loss import AmpGaussianFocalLoss from .necks.second_fpn import SECONDFPN from .task_modules.coders.centerpoint_bbox_coders import CenterPointBBoxCoder from .voxel_encoders.pillar_encoder import BackwardPillarFeatureNet -from .voxel_encoders.pillar_encoder_onnx import BackwardPillarFeatureNetONNX, PillarFeatureNetONNX __all__ = [ "SECOND", @@ -16,11 +13,6 @@ "CenterHead", "CustomSeparateHead", "BackwardPillarFeatureNet", - "PillarFeatureNetONNX", - "BackwardPillarFeatureNetONNX", - "CenterPointONNX", - "CenterHeadONNX", - "SeparateHeadONNX", "CenterPointBBoxCoder", "AmpGaussianFocalLoss", ] diff --git a/projects/CenterPoint/models/detectors/centerpoint_onnx.py b/projects/CenterPoint/models/detectors/centerpoint_onnx.py deleted file mode 100644 index ff568a00d..000000000 --- a/projects/CenterPoint/models/detectors/centerpoint_onnx.py +++ /dev/null @@ -1,176 +0,0 @@ -import os -from typing import Callable, Dict, List, Tuple - -import torch -from mmdet3d.models.detectors.centerpoint import CenterPoint -from mmdet3d.registry import MODELS -from mmengine.logging import MMLogger, print_log -from torch import nn - - -class CenterPointHeadONNX(nn.Module): - """Head module for centerpoint with BACKBONE, NECK and BBOX_HEAD""" - - def __init__(self, backbone: nn.Module, neck: nn.Module, bbox_head: nn.Module): - super(CenterPointHeadONNX, self).__init__() - self.backbone: nn.Module = backbone - self.neck: nn.Module = neck - self.bbox_head: nn.Module = bbox_head - self._logger = MMLogger.get_current_instance() - self._logger.info("Running CenterPointHeadONNX!") - - def forward(self, x: torch.Tensor) -> Tuple[List[Dict[str, torch.Tensor]]]: - """ - Note: - torch.onnx.export() doesn't support triple-nested output - - Args: - x (torch.Tensor): (B, C, H, W) - Returns: - tuple[list[dict[str, any]]]: - (num_classes x [num_detect x {'reg', 'height', 'dim', 'rot', 'vel', 'heatmap'}]) - """ - x = self.backbone(x) - if self.neck is not None: - x = self.neck(x) - x = self.bbox_head(x) - - return x - - -@MODELS.register_module() -class CenterPointONNX(CenterPoint): - """onnx support impl of mmdet3d.models.detectors.CenterPoint""" - - def __init__(self, point_channels: int = 5, device: str = "cpu", **kwargs): - super().__init__(**kwargs) - self._point_channels = point_channels - self._device = device - self._torch_device = torch.device("cuda:0") if self._device == "gpu" else torch.device("cpu") - self._logger = MMLogger.get_current_instance() - self._logger.info("Running CenterPointONNX!") - - def _get_random_inputs(self): - """ - Generate random inputs and preprocess it to feed it to onnx. - """ - # Input channels - points = [ - torch.rand(1000, self._point_channels).to(self._torch_device), - # torch.rand(1000, self._point_channels).to(self._torch_device), - ] - # We only need lidar pointclouds for CenterPoint. - return {"points": points, "data_samples": None} - - def _extract_random_features(self): - assert self.data_preprocessor is not None and hasattr(self.data_preprocessor, "voxelize") - - # Get inputs - inputs = self._get_random_inputs() - voxel_dict = self.data_preprocessor.voxelize(points=inputs["points"], data_samples=inputs["data_samples"]) - assert self.pts_voxel_encoder is not None and hasattr(self.pts_voxel_encoder, "get_input_features") - input_features = self.pts_voxel_encoder.get_input_features( - voxel_dict["voxels"], voxel_dict["num_points"], voxel_dict["coors"] - ) - return input_features, voxel_dict - - def save_onnx( - self, - save_dir: str, - verbose=False, - onnx_opset_version=13, - ): - """Save onnx model - Args: - batch_dict (dict[str, any]) - save_dir (str): directory path to save onnx models - verbose (bool, optional) - onnx_opset_version (int, optional) - """ - print_log(f"Running onnx_opset_version: {onnx_opset_version}") - # Get features - input_features, voxel_dict = self._extract_random_features() - - # === pts_voxel_encoder === - pth_onnx_pve = os.path.join(save_dir, "pts_voxel_encoder.onnx") - torch.onnx.export( - self.pts_voxel_encoder, - (input_features,), - f=pth_onnx_pve, - input_names=("input_features",), - output_names=("pillar_features",), - dynamic_axes={ - "input_features": {0: "num_voxels", 1: "num_max_points"}, - "pillar_features": {0: "num_voxels"}, - }, - verbose=verbose, - opset_version=onnx_opset_version, - ) - print_log(f"Saved pts_voxel_encoder onnx model: {pth_onnx_pve}") - voxel_features = self.pts_voxel_encoder(input_features) - voxel_features = voxel_features.squeeze(1) - - # Note: pts_middle_encoder isn't exported - coors = voxel_dict["coors"] - batch_size = coors[-1, 0] + 1 - x = self.pts_middle_encoder(voxel_features, coors, batch_size) - # x (torch.tensor): (batch_size, num_pillar_features, W, H) - - # === pts_backbone === - assert self.pts_bbox_head is not None and hasattr(self.pts_bbox_head, "output_names") - pts_backbone_neck_head = CenterPointHeadONNX( - self.pts_backbone, - self.pts_neck, - self.pts_bbox_head, - ) - # pts_backbone_neck_head = torch.jit.script(pts_backbone_neck_head) - pth_onnx_backbone_neck_head = os.path.join(save_dir, "pts_backbone_neck_head.onnx") - torch.onnx.export( - pts_backbone_neck_head, - (x,), - f=pth_onnx_backbone_neck_head, - input_names=("spatial_features",), - output_names=tuple(self.pts_bbox_head.output_names), - dynamic_axes={ - name: {0: "batch_size", 2: "H", 3: "W"} - for name in ["spatial_features"] + self.pts_bbox_head.output_names - }, - verbose=verbose, - opset_version=onnx_opset_version, - ) - print_log(f"Saved pts_backbone_neck_head onnx model: {pth_onnx_backbone_neck_head}") - - def save_torchscript( - self, - save_dir: str, - verbose: bool = False, - ): - """Save torchscript model - Args: - batch_dict (dict[str, any]) - save_dir (str): directory path to save onnx models - verbose (bool, optional) - """ - # Get features - input_features, voxel_dict = self._extract_random_features() - - pth_pt_pve = os.path.join(save_dir, "pts_voxel_encoder.pt") - traced_pts_voxel_encoder = torch.jit.trace(self.pts_voxel_encoder, (input_features,)) - traced_pts_voxel_encoder.save(pth_pt_pve) - - voxel_features = traced_pts_voxel_encoder(input_features) - voxel_features = voxel_features.squeeze() - - # Note: pts_middle_encoder isn't exported - coors = voxel_dict["coors"] - batch_size = coors[-1, 0] + 1 - x = self.pts_middle_encoder(voxel_features, coors, batch_size) - - pts_backbone_neck_head = CenterPointHeadONNX( - self.pts_backbone, - self.pts_neck, - self.pts_bbox_head, - ) - pth_pt_head = os.path.join(save_dir, "pts_backbone_neck_head.pt") - traced_pts_backbone_neck_head = torch.jit.trace(pts_backbone_neck_head, (x)) - traced_pts_backbone_neck_head.save(pth_pt_head) diff --git a/projects/CenterPoint/runners/deployment_runner.py b/projects/CenterPoint/runners/deployment_runner.py deleted file mode 100644 index bbd703cbb..000000000 --- a/projects/CenterPoint/runners/deployment_runner.py +++ /dev/null @@ -1,103 +0,0 @@ -from pathlib import Path -from typing import Optional, Union - -from mmengine.registry import MODELS, init_default_scope -from torch import nn - -from autoware_ml.detection3d.runners.base_runner import BaseRunner - - -class DeploymentRunner(BaseRunner): - """Runner to run deploment of mmdet3D model to generate ONNX with random inputs.""" - - def __init__( - self, - model_cfg_path: str, - checkpoint_path: str, - work_dir: Path, - rot_y_axis_reference: bool = False, - device: str = "gpu", - replace_onnx_models: bool = False, - default_scope: str = "mmengine", - experiment_name: str = "", - log_level: Union[int, str] = "INFO", - log_file: Optional[str] = None, - onnx_opset_version: int = 13, - ) -> None: - """ - :param model_cfg_path: MMDet3D model config path. - :param checkpoint_path: Checkpoint path to load weights. - :param work_dir: Working directory to save outputs. - :param rot_y_axis_reference: Set True to convert rotation - from x-axis counterclockwiese to y-axis clockwise. - :param device: Working devices, only 'gpu' or 'cpu' supported. - :param replace_onnx_models: Set True to replace model with ONNX, - for example, CenterHead -> CenterHeadONNX. - :param default_scope: Default scope in mmdet3D. - :param experiment_name: Experiment name. - :param log_level: Logging and display log messages above this level. - :param log_file: Logger file. - :param oxx_opset_version: onnx opset version. - """ - super(DeploymentRunner, self).__init__( - model_cfg_path=model_cfg_path, - checkpoint_path=checkpoint_path, - work_dir=work_dir, - device=device, - default_scope=default_scope, - experiment_name=experiment_name, - log_level=log_level, - log_file=log_file, - ) - - # We need init deafault scope to mmdet3d to search registries in the mmdet3d scope - init_default_scope("mmdet3d") - - self._rot_y_axis_reference = rot_y_axis_reference - self._replace_onnx_models = replace_onnx_models - self._onnx_opset_version = onnx_opset_version - - def build_model(self) -> nn.Module: - """ - Build a model. Replace the model by ONNX model if replace_onnx_model is set. - :return torch.nn.Module. A torch module. - """ - self._logger.info("===== Building CenterPoint model ====") - model_cfg = self._cfg.get("model") - # Update Model type to ONNX - if self._replace_onnx_models: - self._logger.info("Replacing ONNX models!") - model_cfg.type = "CenterPointONNX" - model_cfg.point_channels = model_cfg.pts_voxel_encoder.in_channels - model_cfg.device = self._device - model_cfg.pts_voxel_encoder.type = ( - "PillarFeatureNetONNX" - if model_cfg.pts_voxel_encoder.type == "PillarFeatureNet" - else "BackwardPillarFeatureNetONNX" - ) - model_cfg.pts_bbox_head.type = "CenterHeadONNX" - model_cfg.pts_bbox_head.separate_head.type = "SeparateHeadONNX" - model_cfg.pts_bbox_head.rot_y_axis_reference = self._rot_y_axis_reference - - if model_cfg.pts_backbone.type == "ConvNeXt_PC": - # Always set with_cp (gradient checkpointing) to False for deployment - model_cfg.pts_backbone.with_cp = False - model = MODELS.build(model_cfg) - model.to(self._torch_device) - - self._logger.info(model) - self._logger.info("===== Built CenterPoint model ====") - return model - - def run(self) -> None: - """Start running the Runner.""" - # Building a model - model = self.build_model() - - # Loading checkpoint to the model - self.load_verify_checkpoint(model=model) - - assert hasattr(model, "save_onnx"), "The model must have the function: save_onnx()!" - - # Run and save onnx model! - model.save_onnx(save_dir=self._work_dir, onnx_opset_version=self._onnx_opset_version) diff --git a/projects/CenterPoint/scripts/deploy.py b/projects/CenterPoint/scripts/deploy.py deleted file mode 100644 index 3aea2ee29..000000000 --- a/projects/CenterPoint/scripts/deploy.py +++ /dev/null @@ -1,87 +0,0 @@ -""" -Script to export CenterPoint to onnx/torchscript -""" - -import argparse -import logging -import os -from pathlib import Path - -from projects.CenterPoint.runners.deployment_runner import DeploymentRunner - - -def parse_args(): - parser = argparse.ArgumentParser( - description="Export CenterPoint model to backends.", - ) - parser.add_argument( - "model_cfg_path", - help="model config path", - ) - parser.add_argument( - "checkpoint", - help="model checkpoint path", - ) - parser.add_argument( - "--work-dir", - default="", - help="the dir to save logs and models", - ) - parser.add_argument( - "--log-level", - help="set log level", - default="INFO", - choices=list(logging._nameToLevel.keys()), - ) - parser.add_argument("--onnx_opset_version", type=int, default=13, help="onnx opset version") - parser.add_argument( - "--device", - choices=["cpu", "gpu"], - default="gpu", - help="Set running device!", - ) - parser.add_argument( - "--replace_onnx_models", - action="store_true", - help="Set False to disable replacement of model by ONNX model, for example, CenterHead -> CenterHeadONNX", - ) - parser.add_argument( - "--rot_y_axis_reference", - action="store_true", - help="Set True to output rotation in y-axis clockwise in CenterHeadONNX", - ) - args = parser.parse_args() - return args - - -def build_deploy_runner(args) -> DeploymentRunner: - """Build a DeployRunner.""" - model_cfg_path = args.model_cfg_path - checkpoint_path = args.checkpoint - experiment_name = Path(model_cfg_path).stem - work_dir = ( - Path(os.getcwd()) / "work_dirs" / "deployment" / experiment_name if not args.work_dir else Path(args.work_dir) - ) - - deployment_runner = DeploymentRunner( - experiment_name=experiment_name, - model_cfg_path=model_cfg_path, - checkpoint_path=checkpoint_path, - work_dir=work_dir, - replace_onnx_models=args.replace_onnx_models, - device=args.device, - rot_y_axis_reference=args.rot_y_axis_reference, - onnx_opset_version=args.onnx_opset_version, - ) - return deployment_runner - - -if __name__ == "__main__": - """Launch a DeployRunner.""" - args = parse_args() - - # Build DeploymentRunner - deployment_runner = build_deploy_runner(args=args) - - # Start running DeploymentRunner - deployment_runner.run() From 11780c91df7a151ebc5bbb53318a44bb07c4974e Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 25 Dec 2025 17:44:54 +0900 Subject: [PATCH 02/16] Update projects/CenterPoint/README.md Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- projects/CenterPoint/README.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/projects/CenterPoint/README.md b/projects/CenterPoint/README.md index cc26b910a..cff9fa8e9 100644 --- a/projects/CenterPoint/README.md +++ b/projects/CenterPoint/README.md @@ -115,7 +115,14 @@ where `frame-range` represents the range of frames to visualize. ### 5. Deploy -- Run the unified deployment pipeline to export ONNX/TensorRT artifacts, verify them, and (optionally) evaluate. Update `deployment/projects/centerpoint/config/deploy_config.py` so that `checkpoint_path`, `runtime_io.info_file`, and `export.work_dir` point to your experiment (e.g., `checkpoint_path="work_dirs/centerpoint/t4dataset/second_secfpn_2xb8_121m_base/epoch_50.pth"`). +- Run the unified deployment pipeline: + - Export ONNX/TensorRT artifacts. + - Verify the exported artifacts. + - (Optionally) run evaluation. + - Update `deployment/projects/centerpoint/config/deploy_config.py` so that the following entries point to your experiment: + - `checkpoint_path` (e.g., `checkpoint_path="work_dirs/centerpoint/t4dataset/second_secfpn_2xb8_121m_base/epoch_50.pth"`). + - `runtime_io.info_file`. + - `export.work_dir`. ```sh # Deploy for t4dataset (export + verification + evaluation) From 8e47c767cc7a01644436067a18fae20a5eb6fbee Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 25 Dec 2025 17:45:10 +0900 Subject: [PATCH 03/16] Update deployment/projects/centerpoint/pipelines/tensorrt.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- deployment/projects/centerpoint/pipelines/tensorrt.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py index 525c2bbd1..e0b7843f4 100644 --- a/deployment/projects/centerpoint/pipelines/tensorrt.py +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -68,7 +68,7 @@ def _load_tensorrt_engines(self): context = engine.create_execution_context() if context is None: raise RuntimeError( - f"Failed to create execution context for {component}. " "This is likely due to GPU out-of-memory." + f"Failed to create execution context for {component}. This is likely due to GPU out-of-memory." ) self._engines[component] = engine From bd6e54e1a1dbd231590992a1a01d1e25fc8b1266 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 25 Dec 2025 17:51:12 +0900 Subject: [PATCH 04/16] Update deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- .../onnx_models/pillar_encoder_onnx.py | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py b/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py index 45f81bbde..16ef0eb1f 100644 --- a/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py +++ b/deployment/projects/centerpoint/onnx_models/pillar_encoder_onnx.py @@ -1,7 +1,20 @@ """CenterPoint deploy-only ONNX voxel encoder variants. -These variants expose helper APIs and forward shapes that are friendlier for ONNX export -and componentized inference pipelines. +This module defines ONNX-compatible wrappers around CenterPoint pillar voxel encoders +that are intended for deployment / inference only (that is, for ONNX export and +runtime execution, not for training). The classes here expose helper APIs and forward +signatures that are easier to trace and integrate into componentized inference +pipelines. + +Provided encoder variants include: + +- ``PillarFeatureNetONNX``: ONNX-support implementation of + :class:`mmdet3d.models.voxel_encoders.pillar_encoder.PillarFeatureNet`, keeping + the original behavior but with an ONNX-friendly interface. +- ``BackwardPillarFeatureNetONNX``: backward-compatible pillar feature network based + on :class:`projects.CenterPoint.models.voxel_encoders.pillar_encoder.BackwardPillarFeatureNet` + that prepares pillar features and runs PFN layers without Z-distance features for + use with exported CenterPoint models. """ from typing import Optional From 8cdedff64067389a6561a61686d4b06de06d9ae4 Mon Sep 17 00:00:00 2001 From: "Yi-Hsiang Fang (Vivid)" <146902905+vividf@users.noreply.github.com> Date: Thu, 25 Dec 2025 17:51:21 +0900 Subject: [PATCH 05/16] Update deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> --- .../onnx_models/centerpoint_head_onnx.py | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py b/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py index ee2a85491..2d183264c 100644 --- a/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py +++ b/deployment/projects/centerpoint/onnx_models/centerpoint_head_onnx.py @@ -1,7 +1,22 @@ """CenterPoint deploy-only ONNX head variants. -These heads adjust output ordering and forward behavior to improve ONNX export -and downstream inference compatibility. +This module provides ONNX-friendly implementations of the CenterPoint heads: + +- ``SeparateHeadONNX``: a variant of + :class:`mmdet3d.models.dense_heads.centerpoint_head.SeparateHead` that + redefines the ``heads`` ordering (e.g., ``heatmap``, ``reg``, ``height``, + ``dim``, rotation-related heads, ``vel``) to produce a stable, deterministic + output layout for export. +- ``CenterHeadONNX``: a variant of + :class:`projects.CenterPoint.models.dense_heads.centerpoint_head.CenterHead` + that wraps a single-task ``SeparateHeadONNX`` and exposes an ONNX-oriented + ``forward`` interface, optionally changing the rotation representation to be + relative to the y-axis. + +In this context, *deploy-only* means these classes are intended for model +export and downstream inference (e.g., ONNXRuntime, TensorRT) rather than for +training: they focus on deterministic tensor ordering and export-compatible +forward behavior, and do not add or modify any training-time loss computation. """ from typing import Dict, List, Tuple From d4d55536ade982d07452c3f8ae9ff04f962899de Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 6 Jan 2026 16:17:25 +0900 Subject: [PATCH 06/16] chore: removed comment Signed-off-by: vividf --- deployment/projects/centerpoint/config/deploy_config.py | 3 --- deployment/projects/centerpoint/data_loader.py | 2 -- deployment/projects/centerpoint/evaluator.py | 2 -- deployment/projects/centerpoint/export/component_extractor.py | 2 -- deployment/projects/centerpoint/export/onnx_export_pipeline.py | 2 -- .../projects/centerpoint/export/tensorrt_export_pipeline.py | 2 -- deployment/projects/centerpoint/model_loader.py | 2 -- .../projects/centerpoint/pipelines/centerpoint_pipeline.py | 1 - deployment/projects/centerpoint/pipelines/onnx.py | 2 -- deployment/projects/centerpoint/pipelines/pytorch.py | 2 -- deployment/projects/centerpoint/pipelines/tensorrt.py | 2 -- deployment/projects/centerpoint/runner.py | 2 -- 12 files changed, 24 deletions(-) diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py index e270b3b27..784154d1a 100644 --- a/deployment/projects/centerpoint/config/deploy_config.py +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -1,8 +1,5 @@ """ CenterPoint Deployment Configuration - -NOTE: This file was moved under deployment/projects/centerpoint/config/ as part of the -proposed unified deployment architecture. """ # ============================================================================ diff --git a/deployment/projects/centerpoint/data_loader.py b/deployment/projects/centerpoint/data_loader.py index 0c713a3ea..eb94c14e9 100644 --- a/deployment/projects/centerpoint/data_loader.py +++ b/deployment/projects/centerpoint/data_loader.py @@ -1,7 +1,5 @@ """ CenterPoint DataLoader for deployment. - -Moved from projects/CenterPoint/deploy/data_loader.py into the unified deployment bundle. """ import os diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index 60f1df90e..c0764f2b5 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -1,7 +1,5 @@ """ CenterPoint Evaluator for deployment. - -Moved from projects/CenterPoint/deploy/evaluator.py into the unified deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/export/component_extractor.py b/deployment/projects/centerpoint/export/component_extractor.py index 5c5aed120..64b73ac3c 100644 --- a/deployment/projects/centerpoint/export/component_extractor.py +++ b/deployment/projects/centerpoint/export/component_extractor.py @@ -1,7 +1,5 @@ """ CenterPoint-specific component extractor. - -Moved from projects/CenterPoint/deploy/component_extractor.py into the unified deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/export/onnx_export_pipeline.py b/deployment/projects/centerpoint/export/onnx_export_pipeline.py index 6938336b7..c59a9e048 100644 --- a/deployment/projects/centerpoint/export/onnx_export_pipeline.py +++ b/deployment/projects/centerpoint/export/onnx_export_pipeline.py @@ -1,7 +1,5 @@ """ CenterPoint ONNX export pipeline using composition. - -Moved from deployment/exporters/centerpoint/onnx_export_pipeline.py into the CenterPoint deployment bundle. """ from __future__ import annotations diff --git a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py index d390371b0..67b9a79e7 100644 --- a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py +++ b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py @@ -1,7 +1,5 @@ """ CenterPoint TensorRT export pipeline using composition. - -Moved from deployment/exporters/centerpoint/tensorrt_export_pipeline.py into the CenterPoint deployment bundle. """ from __future__ import annotations diff --git a/deployment/projects/centerpoint/model_loader.py b/deployment/projects/centerpoint/model_loader.py index f48558e63..cd91905b1 100644 --- a/deployment/projects/centerpoint/model_loader.py +++ b/deployment/projects/centerpoint/model_loader.py @@ -1,7 +1,5 @@ """ CenterPoint deployment utilities: ONNX-compatible model building and metrics config extraction. - -Moved from projects/CenterPoint/deploy/utils.py into the unified deployment bundle. """ import copy diff --git a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py index 31015d625..331913448 100644 --- a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py +++ b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py @@ -1,7 +1,6 @@ """ CenterPoint Deployment Pipeline Base Class. -Moved from deployment/pipelines/centerpoint/centerpoint_pipeline.py into the CenterPoint deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/pipelines/onnx.py b/deployment/projects/centerpoint/pipelines/onnx.py index f42713fbc..db4024a1a 100644 --- a/deployment/projects/centerpoint/pipelines/onnx.py +++ b/deployment/projects/centerpoint/pipelines/onnx.py @@ -1,7 +1,5 @@ """ CenterPoint ONNX Pipeline Implementation. - -Moved from deployment/pipelines/centerpoint/centerpoint_onnx.py into the CenterPoint deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/pipelines/pytorch.py b/deployment/projects/centerpoint/pipelines/pytorch.py index 3f43aab55..ed31c7dd1 100644 --- a/deployment/projects/centerpoint/pipelines/pytorch.py +++ b/deployment/projects/centerpoint/pipelines/pytorch.py @@ -1,7 +1,5 @@ """ CenterPoint PyTorch Pipeline Implementation. - -Moved from deployment/pipelines/centerpoint/centerpoint_pytorch.py into the CenterPoint deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py index e0b7843f4..00c452e0d 100644 --- a/deployment/projects/centerpoint/pipelines/tensorrt.py +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -1,7 +1,5 @@ """ CenterPoint TensorRT Pipeline Implementation. - -Moved from deployment/pipelines/centerpoint/centerpoint_tensorrt.py into the CenterPoint deployment bundle. """ import logging diff --git a/deployment/projects/centerpoint/runner.py b/deployment/projects/centerpoint/runner.py index 47e35338e..48599a0b7 100644 --- a/deployment/projects/centerpoint/runner.py +++ b/deployment/projects/centerpoint/runner.py @@ -1,7 +1,5 @@ """ CenterPoint-specific deployment runner. - -Moved from deployment/runners/projects/centerpoint_runner.py into the unified deployment bundle. """ from __future__ import annotations From 52f433dffd9b5ca3253b9394393f5bfa164f1c4f Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 6 Jan 2026 19:00:28 +0900 Subject: [PATCH 07/16] chore: clean up centerpoint export pipeline Signed-off-by: vividf --- deployment/exporters/export_pipelines/base.py | 2 -- .../centerpoint/export/component_extractor.py | 34 ++++++++++++++----- .../export/onnx_export_pipeline.py | 9 ++--- .../export/tensorrt_export_pipeline.py | 19 +++++------ deployment/projects/centerpoint/runner.py | 3 +- deployment/runtime/export_orchestrator.py | 1 - 6 files changed, 40 insertions(+), 28 deletions(-) diff --git a/deployment/exporters/export_pipelines/base.py b/deployment/exporters/export_pipelines/base.py index 1b0ff7d0b..438fc45c6 100644 --- a/deployment/exporters/export_pipelines/base.py +++ b/deployment/exporters/export_pipelines/base.py @@ -55,7 +55,6 @@ def export( output_dir: str, config: BaseDeploymentConfig, device: str, - data_loader: BaseDataLoader, ) -> Artifact: """ Execute the TensorRT export pipeline and return the produced artifact. @@ -65,7 +64,6 @@ def export( output_dir: Directory for output files config: Deployment configuration device: CUDA device string - data_loader: Data loader for samples Returns: Artifact describing the exported TensorRT output diff --git a/deployment/projects/centerpoint/export/component_extractor.py b/deployment/projects/centerpoint/export/component_extractor.py index 64b73ac3c..8a6f6897a 100644 --- a/deployment/projects/centerpoint/export/component_extractor.py +++ b/deployment/projects/centerpoint/export/component_extractor.py @@ -7,9 +7,9 @@ import torch +from deployment.core import BaseDeploymentConfig from deployment.exporters.common.configs import ONNXExportConfig from deployment.exporters.export_pipelines.interfaces import ExportableComponent, ModelComponentExtractor -from deployment.projects.centerpoint.config.deploy_config import model_io, onnx_config from deployment.projects.centerpoint.onnx_models.centerpoint_onnx import CenterPointHeadONNX logger = logging.getLogger(__name__) @@ -23,9 +23,17 @@ class CenterPointComponentExtractor(ModelComponentExtractor): - `backbone_neck_head` (pts_backbone + pts_neck + pts_bbox_head) """ - def __init__(self, logger: logging.Logger = None, simplify: bool = True): + def __init__(self, config: BaseDeploymentConfig, logger: logging.Logger = None): + self.config = config self.logger = logger or logging.getLogger(__name__) - self.simplify = simplify + + @property + def _onnx_config(self) -> dict: + return dict(self.config.onnx_config or {}) + + @property + def _model_io(self) -> dict: + return dict((self.config.deploy_cfg or {}).get("model_io", {}) or {}) def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[ExportableComponent]: input_features, voxel_dict = sample_data @@ -40,6 +48,7 @@ def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[E def _create_voxel_encoder_component( self, model: torch.nn.Module, input_features: torch.Tensor ) -> ExportableComponent: + onnx_config = self._onnx_config voxel_cfg = onnx_config["components"]["voxel_encoder"] return ExportableComponent( name=voxel_cfg["name"], @@ -52,9 +61,9 @@ def _create_voxel_encoder_component( "input_features": {0: "num_voxels", 1: "num_max_points"}, "pillar_features": {0: "num_voxels"}, }, - opset_version=16, + opset_version=onnx_config.get("opset_version", 16), do_constant_folding=True, - simplify=self.simplify, + simplify=bool(onnx_config.get("simplify", True)), save_file=voxel_cfg["onnx_file"], ), ) @@ -72,6 +81,7 @@ def _create_backbone_component( for name in output_names: dynamic_axes[name] = {0: "batch_size", 2: "height", 3: "width"} + onnx_config = self._onnx_config backbone_cfg = onnx_config["components"]["backbone_head"] return ExportableComponent( name=backbone_cfg["name"], @@ -81,9 +91,9 @@ def _create_backbone_component( input_names=("spatial_features",), output_names=output_names, dynamic_axes=dynamic_axes, - opset_version=16, + opset_version=onnx_config.get("opset_version", 16), do_constant_folding=True, - simplify=self.simplify, + simplify=bool(onnx_config.get("simplify", True)), save_file=backbone_cfg["onnx_file"], ), ) @@ -107,7 +117,15 @@ def _get_output_names(self, model: torch.nn.Module) -> Tuple[str, ...]: if isinstance(output_names, (list, tuple)): return tuple(output_names) return (output_names,) - return model_io["head_output_names"] + model_io = self._model_io + output_names = model_io.get("head_output_names", ()) + if not output_names: + raise KeyError( + "Missing head output names for CenterPoint export. " + "Set `model_io.head_output_names` in the deployment config, " + "or define `model.pts_bbox_head.output_names`." + ) + return tuple(output_names) def extract_features(self, model: torch.nn.Module, data_loader: Any, sample_idx: int) -> Tuple[torch.Tensor, dict]: if hasattr(model, "_extract_features"): diff --git a/deployment/projects/centerpoint/export/onnx_export_pipeline.py b/deployment/projects/centerpoint/export/onnx_export_pipeline.py index c59a9e048..7dcbe1165 100644 --- a/deployment/projects/centerpoint/export/onnx_export_pipeline.py +++ b/deployment/projects/centerpoint/export/onnx_export_pipeline.py @@ -53,7 +53,7 @@ def export( sample_data = self._extract_sample_data(model, data_loader, sample_idx) components = self.component_extractor.extract_components(model, sample_data) - exported_paths = self._export_components(components, output_dir_path) + exported_paths = self._export_components(components, output_dir_path, config) self._log_summary(exported_paths) return Artifact(path=str(output_dir_path), multi_file=True) @@ -85,6 +85,7 @@ def _export_components( self, components: Iterable[ExportableComponent], output_dir: Path, + config: BaseDeploymentConfig, ) -> Tuple[str, ...]: exported_paths: list[str] = [] component_list = list(components) @@ -92,7 +93,7 @@ def _export_components( for index, component in enumerate(component_list, start=1): self.logger.info(f"\n[{index}/{total}] Exporting {component.name}...") - exporter = self._build_onnx_exporter() + exporter = self._build_onnx_exporter(config) output_path = output_dir / f"{component.name}.onnx" try: @@ -111,9 +112,9 @@ def _export_components( return tuple(exported_paths) - def _build_onnx_exporter(self): + def _build_onnx_exporter(self, config: BaseDeploymentConfig): return self.exporter_factory.create_onnx_exporter( - config=self.config, + config=config, wrapper_cls=IdentityWrapper, logger=self.logger, ) diff --git a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py index 67b9a79e7..3427c4e4a 100644 --- a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py +++ b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py @@ -11,7 +11,7 @@ import torch -from deployment.core import Artifact, BaseDataLoader, BaseDeploymentConfig +from deployment.core import Artifact, BaseDeploymentConfig from deployment.exporters.common.factory import ExporterFactory from deployment.exporters.export_pipelines.base import TensorRTExportPipeline @@ -49,18 +49,15 @@ def export( output_dir: str, config: BaseDeploymentConfig, device: str, - data_loader: BaseDataLoader, ) -> Artifact: - onnx_dir = onnx_path - if device is None: raise ValueError("CUDA device must be provided for TensorRT export") - if onnx_dir is None: - raise ValueError("onnx_dir must be provided for CenterPoint TensorRT export") + if onnx_path is None: + raise ValueError("onnx_path must be provided for CenterPoint TensorRT export") - onnx_dir_path = Path(onnx_dir) + onnx_dir_path = Path(onnx_path) if not onnx_dir_path.is_dir(): - raise ValueError(f"onnx_path must be a directory for multi-file export, got: {onnx_dir}") + raise ValueError(f"onnx_path must be a directory for multi-file export, got: {onnx_path}") device_id = self._validate_cuda_device(device) torch.cuda.set_device(device_id) @@ -78,7 +75,7 @@ def export( trt_path = output_dir_path / f"{onnx_file.stem}.engine" self.logger.info(f"\n[{i}/{num_files}] Converting {onnx_file.name} → {trt_path.name}...") - exporter = self._build_tensorrt_exporter() + exporter = self._build_tensorrt_exporter(config) artifact = exporter.export( model=None, @@ -97,5 +94,5 @@ def _discover_onnx_files(self, onnx_dir: Path) -> List[Path]: key=lambda p: p.name, ) - def _build_tensorrt_exporter(self): - return self.exporter_factory.create_tensorrt_exporter(config=self.config, logger=self.logger) + def _build_tensorrt_exporter(self, config: BaseDeploymentConfig): + return self.exporter_factory.create_tensorrt_exporter(config=config, logger=self.logger) diff --git a/deployment/projects/centerpoint/runner.py b/deployment/projects/centerpoint/runner.py index 48599a0b7..062cad425 100644 --- a/deployment/projects/centerpoint/runner.py +++ b/deployment/projects/centerpoint/runner.py @@ -34,8 +34,7 @@ def __init__( onnx_pipeline=None, tensorrt_pipeline=None, ): - simplify_onnx = config.get_onnx_settings().simplify - component_extractor = CenterPointComponentExtractor(logger=logger, simplify=simplify_onnx) + component_extractor = CenterPointComponentExtractor(config=config, logger=logger) super().__init__( data_loader=data_loader, diff --git a/deployment/runtime/export_orchestrator.py b/deployment/runtime/export_orchestrator.py index ea540ec39..2546995b4 100644 --- a/deployment/runtime/export_orchestrator.py +++ b/deployment/runtime/export_orchestrator.py @@ -421,7 +421,6 @@ def _export_tensorrt(self, onnx_path: str, context: ExportContext) -> Optional[A output_dir=tensorrt_dir, config=self.config, device=cuda_device, - data_loader=self.data_loader, ) self.artifact_manager.register_artifact(Backend.TENSORRT, artifact) self.logger.info(f"TensorRT export successful: {artifact.path}") From 4a26d9eff80fb0b2089c31f1931a1e29d3f0feed Mon Sep 17 00:00:00 2001 From: vividf Date: Tue, 6 Jan 2026 20:22:08 +0900 Subject: [PATCH 08/16] chore: rename backend config to trt config Signed-off-by: vividf --- deployment/core/__init__.py | 4 +- deployment/core/config/__init__.py | 4 +- deployment/core/config/base_config.py | 29 +++++---- deployment/docs/configuration.md | 2 +- deployment/docs/export_pipeline.md | 9 ++- .../exporters/common/tensorrt_exporter.py | 2 +- .../exporters/export_pipelines/interfaces.py | 29 ++++++++- .../centerpoint/config/deploy_config.py | 15 ++++- .../centerpoint/export/component_extractor.py | 60 ++++++++++++++++++- .../export/onnx_export_pipeline.py | 11 +--- .../export/tensorrt_export_pipeline.py | 24 +++++++- deployment/projects/centerpoint/runner.py | 2 - 12 files changed, 153 insertions(+), 38 deletions(-) diff --git a/deployment/core/__init__.py b/deployment/core/__init__.py index afe64e8b4..3c073b541 100644 --- a/deployment/core/__init__.py +++ b/deployment/core/__init__.py @@ -3,13 +3,13 @@ from deployment.core.artifacts import Artifact from deployment.core.backend import Backend from deployment.core.config.base_config import ( - BackendConfig, BaseDeploymentConfig, DeviceConfig, EvaluationConfig, ExportConfig, ExportMode, RuntimeConfig, + TensorRTConfig, VerificationConfig, VerificationScenario, parse_base_args, @@ -56,7 +56,7 @@ "ExportConfig", "ExportMode", "RuntimeConfig", - "BackendConfig", + "TensorRTConfig", "DeviceConfig", "EvaluationConfig", "VerificationConfig", diff --git a/deployment/core/config/__init__.py b/deployment/core/config/__init__.py index 3197eb73d..7859ffe7e 100644 --- a/deployment/core/config/__init__.py +++ b/deployment/core/config/__init__.py @@ -1,13 +1,13 @@ """Configuration subpackage for deployment core.""" from deployment.core.config.base_config import ( - BackendConfig, BaseDeploymentConfig, EvaluationConfig, ExportConfig, ExportMode, PrecisionPolicy, RuntimeConfig, + TensorRTConfig, VerificationConfig, VerificationScenario, parse_base_args, @@ -16,7 +16,7 @@ from deployment.core.evaluation.base_evaluator import EVALUATION_DEFAULTS, EvaluationDefaults __all__ = [ - "BackendConfig", + "TensorRTConfig", "BaseDeploymentConfig", "EvaluationConfig", "ExportConfig", diff --git a/deployment/core/config/base_config.py b/deployment/core/config/base_config.py index a9f00e573..be155f21d 100644 --- a/deployment/core/config/base_config.py +++ b/deployment/core/config/base_config.py @@ -173,22 +173,31 @@ def from_dict(cls, config_dict: Mapping[str, Any]) -> RuntimeConfig: @dataclass(frozen=True) -class BackendConfig: - """Configuration for backend-specific settings.""" +class TensorRTConfig: + """ + Configuration for TensorRT backend-specific settings. + + Note: + The deploy config key for this section is **`tensorrt_config`**. + """ common_config: Mapping[str, Any] = field(default_factory=_empty_mapping) model_inputs: Tuple[TensorRTModelInputConfig, ...] = field(default_factory=tuple) + components: Mapping[str, Mapping[str, Any]] = field(default_factory=_empty_mapping) @classmethod - def from_dict(cls, config_dict: Mapping[str, Any]) -> BackendConfig: + def from_dict(cls, config_dict: Mapping[str, Any]) -> "TensorRTConfig": common_config = dict(config_dict.get("common_config", {})) model_inputs_raw: Iterable[Mapping[str, Any]] = config_dict.get("model_inputs", []) or [] model_inputs: Tuple[TensorRTModelInputConfig, ...] = tuple( TensorRTModelInputConfig.from_dict(item) for item in model_inputs_raw ) + components_raw = dict(config_dict.get("components", {}) or {}) + components_frozen = {k: MappingProxyType(dict(v or {})) for k, v in components_raw.items()} return cls( common_config=MappingProxyType(common_config), model_inputs=model_inputs, + components=MappingProxyType(components_frozen), ) def get_precision_policy(self) -> str: @@ -315,7 +324,7 @@ def __init__(self, deploy_cfg: Config): # Initialize config sections self.export_config = ExportConfig.from_dict(deploy_cfg.get("export", {})) self.runtime_config = RuntimeConfig.from_dict(deploy_cfg.get("runtime_io", {})) - self.backend_config = BackendConfig.from_dict(deploy_cfg.get("backend_config", {})) + self.tensorrt_config = TensorRTConfig.from_dict(deploy_cfg.get("tensorrt_config", {}) or {}) self._evaluation_config = EvaluationConfig.from_dict(deploy_cfg.get("evaluation", {})) self._verification_config = VerificationConfig.from_dict(deploy_cfg.get("verification", {})) @@ -336,8 +345,8 @@ def _validate_config(self) -> None: raise ValueError(str(exc)) from exc # Validate precision policy if present - backend_cfg = self.deploy_cfg.get("backend_config", {}) - common_cfg = backend_cfg.get("common_config", {}) + tensorrt_config = self.deploy_cfg.get("tensorrt_config", {}) + common_cfg = tensorrt_config.get("common_config", {}) precision_policy = common_cfg.get("precision_policy", PrecisionPolicy.AUTO.value) if precision_policy not in PRECISION_POLICIES: raise ValueError( @@ -512,10 +521,10 @@ def get_tensorrt_settings(self) -> TensorRTExportConfig: TensorRTExportConfig instance containing TensorRT export parameters """ settings_dict = { - "max_workspace_size": self.backend_config.get_max_workspace_size(), - "precision_policy": self.backend_config.get_precision_policy(), - "policy_flags": self.backend_config.get_precision_flags(), - "model_inputs": self.backend_config.model_inputs, + "max_workspace_size": self.tensorrt_config.get_max_workspace_size(), + "precision_policy": self.tensorrt_config.get_precision_policy(), + "policy_flags": self.tensorrt_config.get_precision_flags(), + "model_inputs": self.tensorrt_config.model_inputs, } return TensorRTExportConfig.from_mapping(settings_dict) diff --git a/deployment/docs/configuration.md b/deployment/docs/configuration.md index 06813a335..14f70f34a 100644 --- a/deployment/docs/configuration.md +++ b/deployment/docs/configuration.md @@ -43,7 +43,7 @@ onnx_config = dict( multi_file=False, ) -backend_config = dict( +tensorrt_config = dict( common_config=dict( precision_policy="auto", max_workspace_size=1 << 30, diff --git a/deployment/docs/export_pipeline.md b/deployment/docs/export_pipeline.md index e6a9ed963..856ebc5a0 100644 --- a/deployment/docs/export_pipeline.md +++ b/deployment/docs/export_pipeline.md @@ -21,8 +21,8 @@ CenterPoint splits the model into multiple ONNX/TensorRT artifacts: -- `voxel_encoder.onnx` -- `backbone_head.onnx` +- The produced filenames are driven by `deploy_cfg.onnx_config.components[*].onnx_file` (ONNX) +- The produced engine filenames are driven by `deploy_cfg.tensorrt_config.components[*].engine_file` (TensorRT, optional) Export pipelines orchestrate: @@ -30,6 +30,11 @@ Export pipelines orchestrate: - Input/output wiring between stages. - Directory structure management. +CenterPoint uses a project-specific `ModelComponentExtractor` implementation that provides: + +- `extract_features(model, data_loader, sample_idx)`: project-specific feature extraction for tracing +- `extract_components(model, sample_data)`: splitting into ONNX-exportable submodules and per-component config overrides + ## Verification-Oriented Exports - Exporters register artifacts via `ArtifactManager`, making the exported files discoverable for verification and evaluation. diff --git a/deployment/exporters/common/tensorrt_exporter.py b/deployment/exporters/common/tensorrt_exporter.py index 0ecede689..e160a2226 100644 --- a/deployment/exporters/common/tensorrt_exporter.py +++ b/deployment/exporters/common/tensorrt_exporter.py @@ -312,7 +312,7 @@ def _configure_input_shapes( f" - sample_input: {sample_input}\n" "\n" "Example config:\n" - " backend_config = dict(\n" + " tensorrt_config = dict(\n" " model_inputs=[\n" " dict(\n" " input_shapes={\n" diff --git a/deployment/exporters/export_pipelines/interfaces.py b/deployment/exporters/export_pipelines/interfaces.py index a2ebd7ee7..09524326d 100644 --- a/deployment/exporters/export_pipelines/interfaces.py +++ b/deployment/exporters/export_pipelines/interfaces.py @@ -7,7 +7,7 @@ from abc import ABC, abstractmethod from dataclasses import dataclass -from typing import Any, List, Optional, Tuple +from typing import Any, List, Optional import torch @@ -63,4 +63,29 @@ def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[E Returns: List of ExportableComponent instances ready for ONNX export """ - pass + ... + + @abstractmethod + def extract_features( + self, + model: torch.nn.Module, + data_loader: Any, + sample_idx: int, + ) -> Any: + """ + Extract model-specific intermediate features required for multi-component export. + + Some models require running a portion of the network to generate the input + tensor(s) for later components. This method encapsulates that model-specific + logic and returns a standardized tuple used by `extract_components`. + + Args: + model: PyTorch model used for feature extraction + data_loader: Data loader used to access the sample + sample_idx: Sample index used for tracing/feature extraction + + Returns: + A tuple of (input_features, voxel_dict) or other model-specific payload + that `extract_components` expects. + """ + ... diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py index 784154d1a..e310935f3 100644 --- a/deployment/projects/centerpoint/config/deploy_config.py +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -72,20 +72,19 @@ voxel_encoder=dict( name="pts_voxel_encoder", onnx_file="pts_voxel_encoder.onnx", - engine_file="pts_voxel_encoder.engine", ), backbone_head=dict( name="pts_backbone_neck_head", onnx_file="pts_backbone_neck_head.onnx", - engine_file="pts_backbone_neck_head.engine", ), ), ) + # ============================================================================ # Backend Configuration (mainly for TensorRT) # ============================================================================ -backend_config = dict( +tensorrt_config = dict( common_config=dict( precision_policy="auto", max_workspace_size=2 << 30, @@ -106,6 +105,16 @@ ) ) ], + components=dict( + voxel_encoder=dict( + onnx_file="pts_voxel_encoder.onnx", + engine_file="pts_voxel_encoder.engine", + ), + backbone_head=dict( + onnx_file="pts_backbone_neck_head.onnx", + engine_file="pts_backbone_neck_head.engine", + ), + ), ) # ============================================================================ diff --git a/deployment/projects/centerpoint/export/component_extractor.py b/deployment/projects/centerpoint/export/component_extractor.py index 8a6f6897a..6b677c402 100644 --- a/deployment/projects/centerpoint/export/component_extractor.py +++ b/deployment/projects/centerpoint/export/component_extractor.py @@ -26,6 +26,7 @@ class CenterPointComponentExtractor(ModelComponentExtractor): def __init__(self, config: BaseDeploymentConfig, logger: logging.Logger = None): self.config = config self.logger = logger or logging.getLogger(__name__) + self._validate_config() @property def _onnx_config(self) -> dict: @@ -36,7 +37,7 @@ def _model_io(self) -> dict: return dict((self.config.deploy_cfg or {}).get("model_io", {}) or {}) def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[ExportableComponent]: - input_features, voxel_dict = sample_data + input_features, voxel_dict = self._unpack_sample(sample_data) self.logger.info("Extracting CenterPoint components for export...") voxel_component = self._create_voxel_encoder_component(model, input_features) @@ -45,6 +46,60 @@ def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[E self.logger.info("Extracted 2 components: voxel_encoder, backbone_neck_head") return [voxel_component, backbone_component] + def _validate_config(self) -> None: + onnx_config = self._onnx_config + components = dict(onnx_config.get("components", {}) or {}) + + missing = [] + for required_key in ("voxel_encoder", "backbone_head"): + if required_key not in components: + missing.append(required_key) + if missing: + raise KeyError( + "Missing required `onnx_config.components` entries for CenterPoint export: " + f"{missing}. Please set them in deploy config." + ) + + def _require_fields(comp_key: str, fields: Tuple[str, ...]) -> None: + comp = dict(components.get(comp_key, {}) or {}) + missing_fields = [f for f in fields if not comp.get(f)] + if missing_fields: + raise KeyError( + f"Missing required fields in onnx_config.components['{comp_key}']: {missing_fields}. " + "Expected at least: " + ", ".join(fields) + ) + + _require_fields("voxel_encoder", ("name", "onnx_file")) + _require_fields("backbone_head", ("name", "onnx_file")) + + # Make it easier to debug later failures by flagging likely misconfigurations early. + model_io = self._model_io + if not model_io.get("head_output_names"): + self.logger.warning( + "deploy_cfg.model_io.head_output_names is not set. " + "Export will rely on `model.pts_bbox_head.output_names` at runtime." + ) + + def _unpack_sample(self, sample_data: Any) -> Tuple[torch.Tensor, dict]: + """ + Unpack extractor output into `(input_features, voxel_dict)`. + + We intentionally keep this contract simple to avoid extra project-specific types. + """ + if not (isinstance(sample_data, (list, tuple)) and len(sample_data) == 2): + raise TypeError( + "Invalid sample_data for CenterPoint export. Expected a 2-tuple " + "`(input_features: torch.Tensor, voxel_dict: dict)`." + ) + input_features, voxel_dict = sample_data + if not isinstance(input_features, torch.Tensor): + raise TypeError(f"input_features must be a torch.Tensor, got: {type(input_features)}") + if not isinstance(voxel_dict, dict): + raise TypeError(f"voxel_dict must be a dict, got: {type(voxel_dict)}") + if "coors" not in voxel_dict: + raise KeyError("voxel_dict must contain key 'coors' for CenterPoint export") + return input_features, voxel_dict + def _create_voxel_encoder_component( self, model: torch.nn.Module, input_features: torch.Tensor ) -> ExportableComponent: @@ -129,7 +184,8 @@ def _get_output_names(self, model: torch.nn.Module) -> Tuple[str, ...]: def extract_features(self, model: torch.nn.Module, data_loader: Any, sample_idx: int) -> Tuple[torch.Tensor, dict]: if hasattr(model, "_extract_features"): - return model._extract_features(data_loader, sample_idx) + raw = model._extract_features(data_loader, sample_idx) + return self._unpack_sample(raw) raise AttributeError( "CenterPoint model must have _extract_features method for ONNX export. " "Please ensure the model is built with ONNX compatibility." diff --git a/deployment/projects/centerpoint/export/onnx_export_pipeline.py b/deployment/projects/centerpoint/export/onnx_export_pipeline.py index 7dcbe1165..5b0b06947 100644 --- a/deployment/projects/centerpoint/export/onnx_export_pipeline.py +++ b/deployment/projects/centerpoint/export/onnx_export_pipeline.py @@ -7,7 +7,7 @@ import logging import os from pathlib import Path -from typing import Iterable, Optional, Tuple +from typing import Any, Iterable, Optional, Tuple import torch @@ -29,12 +29,10 @@ def __init__( self, exporter_factory: type[ExporterFactory], component_extractor: ModelComponentExtractor, - config: BaseDeploymentConfig, logger: Optional[logging.Logger] = None, ): self.exporter_factory = exporter_factory self.component_extractor = component_extractor - self.config = config self.logger = logger or logging.getLogger(__name__) def export( @@ -70,10 +68,7 @@ def _extract_sample_data( model: torch.nn.Module, data_loader: BaseDataLoader, sample_idx: int, - ) -> Tuple[torch.Tensor, dict]: - if not hasattr(self.component_extractor, "extract_features"): - raise AttributeError("Component extractor must provide extract_features method") - + ) -> Any: self.logger.info("Extracting features from sample data...") try: return self.component_extractor.extract_features(model, data_loader, sample_idx) @@ -90,10 +85,10 @@ def _export_components( exported_paths: list[str] = [] component_list = list(components) total = len(component_list) + exporter = self._build_onnx_exporter(config) for index, component in enumerate(component_list, start=1): self.logger.info(f"\n[{index}/{total}] Exporting {component.name}...") - exporter = self._build_onnx_exporter(config) output_path = output_dir / f"{component.name}.onnx" try: diff --git a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py index 3427c4e4a..93b98b90a 100644 --- a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py +++ b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py @@ -28,11 +28,9 @@ class CenterPointTensorRTExportPipeline(TensorRTExportPipeline): def __init__( self, exporter_factory: type[ExporterFactory], - config: BaseDeploymentConfig, logger: Optional[logging.Logger] = None, ): self.exporter_factory = exporter_factory - self.config = config self.logger = logger or logging.getLogger(__name__) def _validate_cuda_device(self, device: str) -> int: @@ -70,9 +68,12 @@ def export( if not onnx_files: raise FileNotFoundError(f"No ONNX files found in {onnx_dir_path}") + engine_file_by_onnx_stem = self._build_engine_file_map(config) num_files = len(onnx_files) for i, onnx_file in enumerate(onnx_files, 1): - trt_path = output_dir_path / f"{onnx_file.stem}.engine" + engine_file = engine_file_by_onnx_stem.get(onnx_file.stem, f"{onnx_file.stem}.engine") + trt_path = output_dir_path / engine_file + trt_path.parent.mkdir(parents=True, exist_ok=True) self.logger.info(f"\n[{i}/{num_files}] Converting {onnx_file.name} → {trt_path.name}...") exporter = self._build_tensorrt_exporter(config) @@ -94,5 +95,22 @@ def _discover_onnx_files(self, onnx_dir: Path) -> List[Path]: key=lambda p: p.name, ) + def _build_engine_file_map(self, config: BaseDeploymentConfig) -> dict[str, str]: + """ + Build mapping from ONNX stem -> engine_file from config (if present). + + This allows `deploy_cfg.tensorrt_config.components[*].engine_file` to control output naming. + """ + trt_cfg = getattr(config, "tensorrt_config", None) + components = dict(getattr(trt_cfg, "components", {}) or {}) + mapping: dict[str, str] = {} + for comp in components.values(): + onnx_file = comp.get("onnx_file") + engine_file = comp.get("engine_file") + if not onnx_file or not engine_file: + continue + mapping[Path(onnx_file).stem] = str(engine_file) + return mapping + def _build_tensorrt_exporter(self, config: BaseDeploymentConfig): return self.exporter_factory.create_tensorrt_exporter(config=config, logger=self.logger) diff --git a/deployment/projects/centerpoint/runner.py b/deployment/projects/centerpoint/runner.py index 062cad425..ca2273b89 100644 --- a/deployment/projects/centerpoint/runner.py +++ b/deployment/projects/centerpoint/runner.py @@ -51,14 +51,12 @@ def __init__( self._onnx_pipeline = CenterPointONNXExportPipeline( exporter_factory=ExporterFactory, component_extractor=component_extractor, - config=self.config, logger=self.logger, ) if self._tensorrt_pipeline is None: self._tensorrt_pipeline = CenterPointTensorRTExportPipeline( exporter_factory=ExporterFactory, - config=self.config, logger=self.logger, ) From 1ea169c7573d381565aaa724920aa6280870d23f Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 7 Jan 2026 15:17:15 +0900 Subject: [PATCH 09/16] refactor: refactor deploy config Signed-off-by: vividf --- deployment/docs/configuration.md | 93 ++++++++++- deployment/docs/export_pipeline.md | 61 ++++++- deployment/exporters/common/factory.py | 14 +- .../centerpoint/config/deploy_config.py | 148 +++++++++-------- deployment/projects/centerpoint/evaluator.py | 24 ++- .../centerpoint/export/component_extractor.py | 151 +++++++++++------- .../export/tensorrt_export_pipeline.py | 103 ++++++++++-- .../centerpoint/pipelines/artifacts.py | 64 ++++++++ .../projects/centerpoint/pipelines/factory.py | 24 ++- .../projects/centerpoint/pipelines/onnx.py | 40 ++++- .../centerpoint/pipelines/tensorrt.py | 53 ++++-- 11 files changed, 597 insertions(+), 178 deletions(-) create mode 100644 deployment/projects/centerpoint/pipelines/artifacts.py diff --git a/deployment/docs/configuration.md b/deployment/docs/configuration.md index 14f70f34a..752a66eee 100644 --- a/deployment/docs/configuration.md +++ b/deployment/docs/configuration.md @@ -4,6 +4,10 @@ Configurations remain dictionary-driven for flexibility, with typed dataclasses ## Structure +### Single-Model Export (Simple Models) + +For simple models with a single ONNX/TensorRT output: + ```python # Task type task_type = "detection3d" # or "detection2d", "classification" @@ -40,16 +44,95 @@ onnx_config = dict( opset_version=16, do_constant_folding=True, save_file="model.onnx", - multi_file=False, ) tensorrt_config = dict( - common_config=dict( - precision_policy="auto", - max_workspace_size=1 << 30, + precision_policy="auto", + max_workspace_size=1 << 30, +) +``` + +### Multi-File Export (Complex Models like CenterPoint) + +For models that export to multiple ONNX/TensorRT files, use the unified `components` config: + +```python +task_type = "detection3d" +checkpoint_path = "work_dirs/centerpoint/best_checkpoint.pth" + +devices = dict( + cpu="cpu", + cuda="cuda:0", +) + +export = dict( + mode="both", + work_dir="work_dirs/centerpoint_deployment", +) + +# Unified component configuration (single source of truth) +# Each component defines: name, file paths, IO spec, and TensorRT profile +components = dict( + voxel_encoder=dict( + name="pts_voxel_encoder", + onnx_file="pts_voxel_encoder.onnx", + engine_file="pts_voxel_encoder.engine", + io=dict( + inputs=[dict(name="input_features", dtype="float32")], + outputs=[dict(name="pillar_features", dtype="float32")], + dynamic_axes={ + "input_features": {0: "num_voxels", 1: "num_max_points"}, + "pillar_features": {0: "num_voxels"}, + }, + ), + tensorrt_profile=dict( + input_features=dict( + min_shape=[1000, 32, 11], + opt_shape=[20000, 32, 11], + max_shape=[64000, 32, 11], + ), + ), ), + backbone_head=dict( + name="pts_backbone_neck_head", + onnx_file="pts_backbone_neck_head.onnx", + engine_file="pts_backbone_neck_head.engine", + io=dict( + inputs=[dict(name="spatial_features", dtype="float32")], + outputs=[ + dict(name="heatmap", dtype="float32"), + dict(name="reg", dtype="float32"), + # ... more outputs + ], + dynamic_axes={...}, + ), + tensorrt_profile=dict( + spatial_features=dict( + min_shape=[1, 32, 760, 760], + opt_shape=[1, 32, 760, 760], + max_shape=[1, 32, 760, 760], + ), + ), + ), +) + +# Shared ONNX settings (applied to all components) +onnx_config = dict( + opset_version=16, + do_constant_folding=True, + simplify=False, ) +# Shared TensorRT settings (applied to all components) +tensorrt_config = dict( + precision_policy="auto", + max_workspace_size=2 << 30, +) +``` + +### Verification and Evaluation + +```python verification = dict( enabled=True, num_verify_samples=3, @@ -138,4 +221,4 @@ Use `from_mapping()` / `from_dict()` helpers to instantiate typed configs from e ## Example Config Paths -- `deployment/projects/centerpoint/config/deploy_config.py` +- `deployment/projects/centerpoint/config/deploy_config.py` - Multi-file export example diff --git a/deployment/docs/export_pipeline.md b/deployment/docs/export_pipeline.md index 856ebc5a0..2fe5ffe7a 100644 --- a/deployment/docs/export_pipeline.md +++ b/deployment/docs/export_pipeline.md @@ -19,16 +19,50 @@ ## Multi-File Export (CenterPoint) -CenterPoint splits the model into multiple ONNX/TensorRT artifacts: +CenterPoint splits the model into multiple ONNX/TensorRT artifacts using a unified `components` configuration: -- The produced filenames are driven by `deploy_cfg.onnx_config.components[*].onnx_file` (ONNX) -- The produced engine filenames are driven by `deploy_cfg.tensorrt_config.components[*].engine_file` (TensorRT, optional) +```python +components = dict( + voxel_encoder=dict( + name="pts_voxel_encoder", + onnx_file="pts_voxel_encoder.onnx", # ONNX output filename + engine_file="pts_voxel_encoder.engine", # TensorRT output filename + io=dict( + inputs=[dict(name="input_features", dtype="float32")], + outputs=[dict(name="pillar_features", dtype="float32")], + dynamic_axes={...}, + ), + tensorrt_profile=dict( + input_features=dict(min_shape=[...], opt_shape=[...], max_shape=[...]), + ), + ), + backbone_head=dict( + name="pts_backbone_neck_head", + onnx_file="pts_backbone_neck_head.onnx", + engine_file="pts_backbone_neck_head.engine", + io=dict(...), + tensorrt_profile=dict(...), + ), +) +``` + +### Configuration Structure + +Each component in `deploy_cfg.components` defines: + +- `name`: Component identifier used during export +- `onnx_file`: Output ONNX filename +- `engine_file`: Output TensorRT engine filename +- `io`: Input/output specification (names, dtypes, dynamic_axes) +- `tensorrt_profile`: TensorRT optimization profile (min/opt/max shapes) + +### Export Pipeline Orchestration Export pipelines orchestrate: -- Sequential export of each component. -- Input/output wiring between stages. -- Directory structure management. +- Sequential export of each component +- Input/output wiring between stages +- Directory structure management CenterPoint uses a project-specific `ModelComponentExtractor` implementation that provides: @@ -53,3 +87,18 @@ runner = CenterPointDeploymentRunner( ``` Simple projects can skip export pipelines entirely and rely on the base exporters provided by `ExporterFactory`. + +## Runtime Pipeline Usage + +Runtime pipelines receive the `components_cfg` through constructor injection: + +```python +pipeline = CenterPointONNXPipeline( + pytorch_model=model, + onnx_dir="/path/to/onnx", + device="cuda:0", + components_cfg=deploy_cfg["components"], # Pass component config +) +``` + +This allows pipelines to resolve artifact paths from the unified config. diff --git a/deployment/exporters/common/factory.py b/deployment/exporters/common/factory.py index 9533f2d12..c58192890 100644 --- a/deployment/exporters/common/factory.py +++ b/deployment/exporters/common/factory.py @@ -5,9 +5,10 @@ from __future__ import annotations import logging -from typing import Type +from typing import Optional, Type from deployment.core import BaseDeploymentConfig +from deployment.exporters.common.configs import TensorRTExportConfig from deployment.exporters.common.model_wrappers import BaseModelWrapper from deployment.exporters.common.onnx_exporter import ONNXExporter from deployment.exporters.common.tensorrt_exporter import TensorRTExporter @@ -38,12 +39,21 @@ def create_onnx_exporter( def create_tensorrt_exporter( config: BaseDeploymentConfig, logger: logging.Logger, + config_override: Optional[TensorRTExportConfig] = None, ) -> TensorRTExporter: """ Build a TensorRT exporter using the deployment config settings. + + Args: + config: Deployment configuration + logger: Logger instance + config_override: Optional TensorRT config to use instead of the one + derived from the deployment config. Useful for + per-component configurations in multi-file exports. """ + trt_config = config_override if config_override is not None else config.get_tensorrt_settings() return TensorRTExporter( - config=config.get_tensorrt_settings(), + config=trt_config, logger=logger, ) diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py index e310935f3..f64136516 100644 --- a/deployment/projects/centerpoint/config/deploy_config.py +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -30,6 +30,82 @@ onnx_path=None, ) +# Derived artifact directories +_WORK_DIR = str(export["work_dir"]).rstrip("/") +_ONNX_DIR = f"{_WORK_DIR}/onnx" +_TENSORRT_DIR = f"{_WORK_DIR}/tensorrt" + +# ============================================================================ +# Unified Component Configuration (Single Source of Truth) +# +# Each component defines: +# - name: Component identifier used in export +# - onnx_file: Output ONNX filename +# - engine_file: Output TensorRT engine filename +# - io: Input/output specification for ONNX export +# - tensorrt_profile: TensorRT optimization profile (min/opt/max shapes) +# ============================================================================ +components = dict( + voxel_encoder=dict( + name="pts_voxel_encoder", + onnx_file="pts_voxel_encoder.onnx", + engine_file="pts_voxel_encoder.engine", + io=dict( + inputs=[ + dict(name="input_features", dtype="float32"), + ], + outputs=[ + dict(name="pillar_features", dtype="float32"), + ], + dynamic_axes={ + "input_features": {0: "num_voxels", 1: "num_max_points"}, + "pillar_features": {0: "num_voxels"}, + }, + ), + tensorrt_profile=dict( + input_features=dict( + min_shape=[1000, 32, 11], + opt_shape=[20000, 32, 11], + max_shape=[64000, 32, 11], + ), + ), + ), + backbone_head=dict( + name="pts_backbone_neck_head", + onnx_file="pts_backbone_neck_head.onnx", + engine_file="pts_backbone_neck_head.engine", + io=dict( + inputs=[ + dict(name="spatial_features", dtype="float32"), + ], + outputs=[ + dict(name="heatmap", dtype="float32"), + dict(name="reg", dtype="float32"), + dict(name="height", dtype="float32"), + dict(name="dim", dtype="float32"), + dict(name="rot", dtype="float32"), + dict(name="vel", dtype="float32"), + ], + dynamic_axes={ + "spatial_features": {0: "batch_size", 2: "height", 3: "width"}, + "heatmap": {0: "batch_size", 2: "height", 3: "width"}, + "reg": {0: "batch_size", 2: "height", 3: "width"}, + "height": {0: "batch_size", 2: "height", 3: "width"}, + "dim": {0: "batch_size", 2: "height", 3: "width"}, + "rot": {0: "batch_size", 2: "height", 3: "width"}, + "vel": {0: "batch_size", 2: "height", 3: "width"}, + }, + ), + tensorrt_profile=dict( + spatial_features=dict( + min_shape=[1, 32, 760, 760], + opt_shape=[1, 32, 760, 760], + max_shape=[1, 32, 760, 760], + ), + ), + ), +) + # ============================================================================ # Runtime I/O settings # ============================================================================ @@ -39,27 +115,7 @@ ) # ============================================================================ -# Model Input/Output Configuration -# ============================================================================ -model_io = dict( - input_name="voxels", - input_shape=(32, 4), - input_dtype="float32", - additional_inputs=[ - dict(name="num_points", shape=(-1,), dtype="int32"), - dict(name="coors", shape=(-1, 4), dtype="int32"), - ], - head_output_names=("heatmap", "reg", "height", "dim", "rot", "vel"), - batch_size=None, - dynamic_axes={ - "voxels": {0: "num_voxels"}, - "num_points": {0: "num_voxels"}, - "coors": {0: "num_voxels"}, - }, -) - -# ============================================================================ -# ONNX Export Configuration +# ONNX Export Settings (shared across all components) # ============================================================================ onnx_config = dict( opset_version=16, @@ -67,54 +123,14 @@ export_params=True, keep_initializers_as_inputs=False, simplify=False, - multi_file=True, - components=dict( - voxel_encoder=dict( - name="pts_voxel_encoder", - onnx_file="pts_voxel_encoder.onnx", - ), - backbone_head=dict( - name="pts_backbone_neck_head", - onnx_file="pts_backbone_neck_head.onnx", - ), - ), ) - # ============================================================================ -# Backend Configuration (mainly for TensorRT) +# TensorRT Build Settings (shared across all components) # ============================================================================ tensorrt_config = dict( - common_config=dict( - precision_policy="auto", - max_workspace_size=2 << 30, - ), - model_inputs=[ - dict( - input_shapes=dict( - input_features=dict( - min_shape=[1000, 32, 11], - opt_shape=[20000, 32, 11], - max_shape=[64000, 32, 11], - ), - spatial_features=dict( - min_shape=[1, 32, 760, 760], - opt_shape=[1, 32, 760, 760], - max_shape=[1, 32, 760, 760], - ), - ) - ) - ], - components=dict( - voxel_encoder=dict( - onnx_file="pts_voxel_encoder.onnx", - engine_file="pts_voxel_encoder.engine", - ), - backbone_head=dict( - onnx_file="pts_backbone_neck_head.onnx", - engine_file="pts_backbone_neck_head.engine", - ), - ), + precision_policy="auto", + max_workspace_size=2 << 30, ) # ============================================================================ @@ -132,12 +148,12 @@ onnx=dict( enabled=True, device=devices["cuda"], - model_dir="work_dirs/centerpoint_deployment/onnx/", + model_dir=_ONNX_DIR, ), tensorrt=dict( enabled=True, device=devices["cuda"], - engine_dir="work_dirs/centerpoint_deployment/tensorrt/", + engine_dir=_TENSORRT_DIR, ), ), ) diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index c0764f2b5..a44fb8462 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -3,7 +3,7 @@ """ import logging -from typing import Any, Dict, List, Tuple +from typing import Any, Dict, List, Mapping, Optional, Tuple from mmengine.config import Config @@ -17,7 +17,6 @@ ) from deployment.core.io.base_data_loader import BaseDataLoader from deployment.pipelines.factory import PipelineFactory -from deployment.projects.centerpoint.config.deploy_config import model_io logger = logging.getLogger(__name__) @@ -27,18 +26,27 @@ class CenterPointEvaluator(BaseEvaluator): This builds a task profile (class names, display name) and uses the configured `Detection3DMetricsInterface` to compute metrics from pipeline outputs. + + Args: + model_cfg: Model configuration with class_names + metrics_config: Configuration for 3D detection metrics + components_cfg: Optional unified components configuration dict. + Used to get output names from components.backbone_head.io.outputs """ def __init__( self, model_cfg: Config, metrics_config: Detection3DMetricsConfig, + components_cfg: Optional[Mapping[str, Any]] = None, ): if hasattr(model_cfg, "class_names"): class_names = model_cfg.class_names else: raise ValueError("class_names must be provided via model_cfg.class_names.") + self._components_cfg = components_cfg or {} + task_profile = TaskProfile( task_name="centerpoint_3d_detection", display_name="CenterPoint 3D Object Detection", @@ -58,7 +66,16 @@ def set_onnx_config(self, model_cfg: Config) -> None: self.model_cfg = model_cfg def _get_output_names(self) -> List[str]: - return list(model_io["head_output_names"]) + """Get head output names from components config.""" + backbone_head_cfg = self._components_cfg.get("backbone_head", {}) + io_cfg = backbone_head_cfg.get("io", {}) + outputs = io_cfg.get("outputs", []) + + if outputs: + return [out.get("name") for out in outputs if out.get("name")] + + # Fallback to default output names + return ["heatmap", "reg", "height", "dim", "rot", "vel"] def _create_pipeline(self, model_spec: ModelSpec, device: str) -> Any: return PipelineFactory.create( @@ -66,6 +83,7 @@ def _create_pipeline(self, model_spec: ModelSpec, device: str) -> Any: model_spec=model_spec, pytorch_model=self.pytorch_model, device=device, + components_cfg=self._components_cfg, ) def _prepare_input( diff --git a/deployment/projects/centerpoint/export/component_extractor.py b/deployment/projects/centerpoint/export/component_extractor.py index 6b677c402..e7bce1744 100644 --- a/deployment/projects/centerpoint/export/component_extractor.py +++ b/deployment/projects/centerpoint/export/component_extractor.py @@ -1,9 +1,11 @@ """ CenterPoint-specific component extractor. + +Extracts exportable submodules from CenterPoint using the unified component config. """ import logging -from typing import Any, List, Tuple +from typing import Any, Dict, List, Mapping, Tuple import torch @@ -21,6 +23,9 @@ class CenterPointComponentExtractor(ModelComponentExtractor): For CenterPoint we export two components: - `voxel_encoder` (pts_voxel_encoder) - `backbone_neck_head` (pts_backbone + pts_neck + pts_bbox_head) + + Uses the unified `components` config structure where each component defines + its own IO specification, filenames, and TensorRT profiles. """ def __init__(self, config: BaseDeploymentConfig, logger: logging.Logger = None): @@ -29,12 +34,14 @@ def __init__(self, config: BaseDeploymentConfig, logger: logging.Logger = None): self._validate_config() @property - def _onnx_config(self) -> dict: - return dict(self.config.onnx_config or {}) + def _components_cfg(self) -> Dict[str, Any]: + """Get unified components configuration.""" + return dict((self.config.deploy_cfg or {}).get("components", {}) or {}) @property - def _model_io(self) -> dict: - return dict((self.config.deploy_cfg or {}).get("model_io", {}) or {}) + def _onnx_config(self) -> Dict[str, Any]: + """Get shared ONNX export settings.""" + return dict(self.config.onnx_config or {}) def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[ExportableComponent]: input_features, voxel_dict = self._unpack_sample(sample_data) @@ -47,8 +54,8 @@ def extract_components(self, model: torch.nn.Module, sample_data: Any) -> List[E return [voxel_component, backbone_component] def _validate_config(self) -> None: - onnx_config = self._onnx_config - components = dict(onnx_config.get("components", {}) or {}) + """Validate component configuration.""" + components = self._components_cfg missing = [] for required_key in ("voxel_encoder", "backbone_head"): @@ -56,7 +63,7 @@ def _validate_config(self) -> None: missing.append(required_key) if missing: raise KeyError( - "Missing required `onnx_config.components` entries for CenterPoint export: " + "Missing required `components` entries for CenterPoint export: " f"{missing}. Please set them in deploy config." ) @@ -65,21 +72,13 @@ def _require_fields(comp_key: str, fields: Tuple[str, ...]) -> None: missing_fields = [f for f in fields if not comp.get(f)] if missing_fields: raise KeyError( - f"Missing required fields in onnx_config.components['{comp_key}']: {missing_fields}. " + f"Missing required fields in components['{comp_key}']: {missing_fields}. " "Expected at least: " + ", ".join(fields) ) _require_fields("voxel_encoder", ("name", "onnx_file")) _require_fields("backbone_head", ("name", "onnx_file")) - # Make it easier to debug later failures by flagging likely misconfigurations early. - model_io = self._model_io - if not model_io.get("head_output_names"): - self.logger.warning( - "deploy_cfg.model_io.head_output_names is not set. " - "Export will rely on `model.pts_bbox_head.output_names` at runtime." - ) - def _unpack_sample(self, sample_data: Any) -> Tuple[torch.Tensor, dict]: """ Unpack extractor output into `(input_features, voxel_dict)`. @@ -100,56 +99,85 @@ def _unpack_sample(self, sample_data: Any) -> Tuple[torch.Tensor, dict]: raise KeyError("voxel_dict must contain key 'coors' for CenterPoint export") return input_features, voxel_dict + def _get_component_io(self, component: str) -> Mapping[str, Any]: + """Get IO specification for a component.""" + comp_cfg = self._components_cfg.get(component, {}) + return comp_cfg.get("io", {}) + + def _build_onnx_config_for_component( + self, + component: str, + input_names: Tuple[str, ...], + output_names: Tuple[str, ...], + dynamic_axes: Dict[str, Dict[int, str]] | None = None, + ) -> ONNXExportConfig: + """Build ONNX export config for a component using unified config.""" + comp_cfg = self._components_cfg.get(component, {}) + comp_io = comp_cfg.get("io", {}) + onnx_settings = self._onnx_config + + # Use dynamic_axes from component IO config if not explicitly provided + if dynamic_axes is None: + dynamic_axes = comp_io.get("dynamic_axes", {}) + + return ONNXExportConfig( + input_names=input_names, + output_names=output_names, + dynamic_axes=dynamic_axes, + opset_version=onnx_settings.get("opset_version", 16), + do_constant_folding=onnx_settings.get("do_constant_folding", True), + simplify=bool(onnx_settings.get("simplify", True)), + save_file=comp_cfg.get("onnx_file", f"{component}.onnx"), + ) + def _create_voxel_encoder_component( self, model: torch.nn.Module, input_features: torch.Tensor ) -> ExportableComponent: - onnx_config = self._onnx_config - voxel_cfg = onnx_config["components"]["voxel_encoder"] + """Create exportable component for voxel encoder.""" + comp_cfg = self._components_cfg["voxel_encoder"] + comp_io = comp_cfg.get("io", {}) + + # Get input/output names from IO config + inputs = comp_io.get("inputs", []) + outputs = comp_io.get("outputs", []) + input_names = tuple(inp.get("name", "input_features") for inp in inputs) or ("input_features",) + output_names = tuple(out.get("name", "pillar_features") for out in outputs) or ("pillar_features",) + return ExportableComponent( - name=voxel_cfg["name"], + name=comp_cfg["name"], module=model.pts_voxel_encoder, sample_input=input_features, - config_override=ONNXExportConfig( - input_names=("input_features",), - output_names=("pillar_features",), - dynamic_axes={ - "input_features": {0: "num_voxels", 1: "num_max_points"}, - "pillar_features": {0: "num_voxels"}, - }, - opset_version=onnx_config.get("opset_version", 16), - do_constant_folding=True, - simplify=bool(onnx_config.get("simplify", True)), - save_file=voxel_cfg["onnx_file"], + config_override=self._build_onnx_config_for_component( + component="voxel_encoder", + input_names=input_names, + output_names=output_names, ), ) def _create_backbone_component( self, model: torch.nn.Module, input_features: torch.Tensor, voxel_dict: dict ) -> ExportableComponent: + """Create exportable component for backbone + neck + head.""" backbone_input = self._prepare_backbone_input(model, input_features, voxel_dict) backbone_module = self._create_backbone_module(model) - output_names = self._get_output_names(model) - dynamic_axes = { - "spatial_features": {0: "batch_size", 2: "height", 3: "width"}, - } - for name in output_names: - dynamic_axes[name] = {0: "batch_size", 2: "height", 3: "width"} + comp_cfg = self._components_cfg["backbone_head"] + comp_io = comp_cfg.get("io", {}) + + # Get input/output names from IO config + inputs = comp_io.get("inputs", []) + outputs = comp_io.get("outputs", []) + input_names = tuple(inp.get("name", "spatial_features") for inp in inputs) or ("spatial_features",) + output_names = self._get_output_names(model, outputs) - onnx_config = self._onnx_config - backbone_cfg = onnx_config["components"]["backbone_head"] return ExportableComponent( - name=backbone_cfg["name"], + name=comp_cfg["name"], module=backbone_module, sample_input=backbone_input, - config_override=ONNXExportConfig( - input_names=("spatial_features",), + config_override=self._build_onnx_config_for_component( + component="backbone_head", + input_names=input_names, output_names=output_names, - dynamic_axes=dynamic_axes, - opset_version=onnx_config.get("opset_version", 16), - do_constant_folding=True, - simplify=bool(onnx_config.get("simplify", True)), - save_file=backbone_cfg["onnx_file"], ), ) @@ -166,21 +194,30 @@ def _prepare_backbone_input( def _create_backbone_module(self, model: torch.nn.Module) -> torch.nn.Module: return CenterPointHeadONNX(model.pts_backbone, model.pts_neck, model.pts_bbox_head) - def _get_output_names(self, model: torch.nn.Module) -> Tuple[str, ...]: + def _get_output_names(self, model: torch.nn.Module, io_outputs: List[Dict[str, Any]]) -> Tuple[str, ...]: + """Get output names from config or model. + + Priority: + 1. Component IO config outputs + 2. model.pts_bbox_head.output_names + 3. Raise error if neither available + """ + # Try from component IO config first + if io_outputs: + return tuple(out.get("name") for out in io_outputs if out.get("name")) + + # Try from model if hasattr(model, "pts_bbox_head") and hasattr(model.pts_bbox_head, "output_names"): output_names = model.pts_bbox_head.output_names if isinstance(output_names, (list, tuple)): return tuple(output_names) return (output_names,) - model_io = self._model_io - output_names = model_io.get("head_output_names", ()) - if not output_names: - raise KeyError( - "Missing head output names for CenterPoint export. " - "Set `model_io.head_output_names` in the deployment config, " - "or define `model.pts_bbox_head.output_names`." - ) - return tuple(output_names) + + raise KeyError( + "Missing head output names for CenterPoint export. " + "Set `components.backbone_head.io.outputs` in the deployment config, " + "or define `model.pts_bbox_head.output_names`." + ) def extract_features(self, model: torch.nn.Module, data_loader: Any, sample_idx: int) -> Tuple[torch.Tensor, dict]: if hasattr(model, "_extract_features"): diff --git a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py index 93b98b90a..ba5fb8525 100644 --- a/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py +++ b/deployment/projects/centerpoint/export/tensorrt_export_pipeline.py @@ -7,11 +7,12 @@ import logging import re from pathlib import Path -from typing import List, Optional +from typing import Any, Dict, List, Mapping, Optional import torch from deployment.core import Artifact, BaseDeploymentConfig +from deployment.exporters.common.configs import TensorRTExportConfig, TensorRTModelInputConfig, TensorRTProfileConfig from deployment.exporters.common.factory import ExporterFactory from deployment.exporters.export_pipelines.base import TensorRTExportPipeline @@ -21,6 +22,7 @@ class CenterPointTensorRTExportPipeline(TensorRTExportPipeline): Consumes a directory of ONNX files (multi-file export) and builds a TensorRT engine per component into `output_dir`. + """ _CUDA_DEVICE_PATTERN = re.compile(r"^cuda:\d+$") @@ -68,15 +70,22 @@ def export( if not onnx_files: raise FileNotFoundError(f"No ONNX files found in {onnx_dir_path}") - engine_file_by_onnx_stem = self._build_engine_file_map(config) + components_cfg = self._get_components_cfg(config) + engine_file_map = self._build_engine_file_map(components_cfg) + onnx_stem_to_component = self._build_onnx_stem_to_component_map(components_cfg) + num_files = len(onnx_files) for i, onnx_file in enumerate(onnx_files, 1): - engine_file = engine_file_by_onnx_stem.get(onnx_file.stem, f"{onnx_file.stem}.engine") + onnx_stem = onnx_file.stem + engine_file = engine_file_map.get(onnx_stem, f"{onnx_stem}.engine") trt_path = output_dir_path / engine_file trt_path.parent.mkdir(parents=True, exist_ok=True) self.logger.info(f"\n[{i}/{num_files}] Converting {onnx_file.name} → {trt_path.name}...") - exporter = self._build_tensorrt_exporter(config) + + # Get component-specific TensorRT profile + component_name = onnx_stem_to_component.get(onnx_stem) + exporter = self._build_tensorrt_exporter_for_component(config, components_cfg, component_name) artifact = exporter.export( model=None, @@ -95,16 +104,12 @@ def _discover_onnx_files(self, onnx_dir: Path) -> List[Path]: key=lambda p: p.name, ) - def _build_engine_file_map(self, config: BaseDeploymentConfig) -> dict[str, str]: - """ - Build mapping from ONNX stem -> engine_file from config (if present). - - This allows `deploy_cfg.tensorrt_config.components[*].engine_file` to control output naming. - """ - trt_cfg = getattr(config, "tensorrt_config", None) - components = dict(getattr(trt_cfg, "components", {}) or {}) - mapping: dict[str, str] = {} - for comp in components.values(): + def _build_engine_file_map(self, components_cfg: Mapping[str, Any]) -> Dict[str, str]: + """Build mapping from ONNX stem -> engine_file.""" + mapping: Dict[str, str] = {} + for comp in components_cfg.values(): + if not isinstance(comp, Mapping): + continue onnx_file = comp.get("onnx_file") engine_file = comp.get("engine_file") if not onnx_file or not engine_file: @@ -112,5 +117,71 @@ def _build_engine_file_map(self, config: BaseDeploymentConfig) -> dict[str, str] mapping[Path(onnx_file).stem] = str(engine_file) return mapping - def _build_tensorrt_exporter(self, config: BaseDeploymentConfig): - return self.exporter_factory.create_tensorrt_exporter(config=config, logger=self.logger) + def _build_onnx_stem_to_component_map(self, components_cfg: Mapping[str, Any]) -> Dict[str, str]: + """Build mapping from ONNX stem -> component name.""" + mapping: Dict[str, str] = {} + for comp_name, comp_cfg in components_cfg.items(): + if not isinstance(comp_cfg, Mapping): + continue + onnx_file = comp_cfg.get("onnx_file") + if onnx_file: + mapping[Path(onnx_file).stem] = comp_name + return mapping + + def _get_components_cfg(self, config: BaseDeploymentConfig) -> Mapping[str, Any]: + """Get unified components configuration from deploy config.""" + return dict((config.deploy_cfg or {}).get("components", {}) or {}) + + def _build_tensorrt_exporter_for_component( + self, + config: BaseDeploymentConfig, + components_cfg: Mapping[str, Any], + component_name: Optional[str], + ): + """Build TensorRT exporter with component-specific profile. + + Converts the unified `tensorrt_profile` from the component config + into the `model_inputs` format expected by TensorRTExporter. + """ + # Get base TensorRT settings from config + trt_cfg = config.deploy_cfg.get("tensorrt_config", {}) or {} + precision_policy = trt_cfg.get("precision_policy", "auto") + max_workspace_size = trt_cfg.get("max_workspace_size", 1 << 30) + + # Build model_inputs from component's tensorrt_profile + model_inputs = () + if component_name and component_name in components_cfg: + comp_cfg = components_cfg[component_name] + tensorrt_profile = comp_cfg.get("tensorrt_profile", {}) + + if tensorrt_profile: + # Convert tensorrt_profile to TensorRTModelInputConfig format + input_shapes = {} + for input_name, shape_cfg in tensorrt_profile.items(): + if isinstance(shape_cfg, Mapping): + input_shapes[input_name] = TensorRTProfileConfig( + min_shape=tuple(shape_cfg.get("min_shape", [])), + opt_shape=tuple(shape_cfg.get("opt_shape", [])), + max_shape=tuple(shape_cfg.get("max_shape", [])), + ) + + if input_shapes: + from types import MappingProxyType + + model_inputs = (TensorRTModelInputConfig(input_shapes=MappingProxyType(input_shapes)),) + self.logger.info( + f"Using TensorRT profile for component '{component_name}': {list(input_shapes.keys())}" + ) + + # Create TensorRT export config with component-specific model_inputs + trt_export_config = TensorRTExportConfig( + precision_policy=precision_policy, + max_workspace_size=max_workspace_size, + model_inputs=model_inputs, + ) + + return self.exporter_factory.create_tensorrt_exporter( + config=config, + logger=self.logger, + config_override=trt_export_config, + ) diff --git a/deployment/projects/centerpoint/pipelines/artifacts.py b/deployment/projects/centerpoint/pipelines/artifacts.py new file mode 100644 index 000000000..34d5ea0e7 --- /dev/null +++ b/deployment/projects/centerpoint/pipelines/artifacts.py @@ -0,0 +1,64 @@ +""" +Artifact path helpers for CenterPoint pipelines. + +Resolves component artifact paths from the unified deploy config. +""" + +from __future__ import annotations + +import os.path as osp +from typing import Any, Mapping + + +def resolve_component_artifact_path( + *, + base_dir: str, + components_cfg: Mapping[str, Any], + component: str, + file_key: str, + default_filename: str, +) -> str: + """Resolve an artifact path for one component. + + Args: + base_dir: Base directory for artifacts (onnx_dir or tensorrt_dir) + components_cfg: The unified `components` dict from deploy_config + component: Component name (e.g., 'voxel_encoder', 'backbone_head') + file_key: Key to look up ('onnx_file' or 'engine_file') + default_filename: Fallback filename if not specified in config + + Returns: + Absolute path to the artifact file + + Priority: + - `components_cfg[component][file_key]` if present + - otherwise `default_filename` + + Supports absolute paths in config; otherwise joins with `base_dir`. + """ + comp_cfg = components_cfg.get(component, {}) or {} + if not isinstance(comp_cfg, Mapping): + raise TypeError(f"components['{component}'] must be a mapping, got {type(comp_cfg)}") + + filename = comp_cfg.get(file_key, default_filename) + if not isinstance(filename, str) or not filename: + raise TypeError(f"components['{component}']['{file_key}'] must be a non-empty str, got {type(filename)}") + + return filename if osp.isabs(filename) else osp.join(base_dir, filename) + + +def get_component_files(components_cfg: Mapping[str, Any], file_key: str) -> dict[str, str]: + """Get all component filenames for a given file type. + + Args: + components_cfg: The unified `components` dict from deploy_config + file_key: Key to look up ('onnx_file' or 'engine_file') + + Returns: + Dict mapping component name to filename + """ + result = {} + for comp_name, comp_cfg in components_cfg.items(): + if isinstance(comp_cfg, Mapping) and file_key in comp_cfg: + result[comp_name] = comp_cfg[file_key] + return result diff --git a/deployment/projects/centerpoint/pipelines/factory.py b/deployment/projects/centerpoint/pipelines/factory.py index af3bfceab..e6822bd50 100644 --- a/deployment/projects/centerpoint/pipelines/factory.py +++ b/deployment/projects/centerpoint/pipelines/factory.py @@ -6,7 +6,7 @@ """ import logging -from typing import Any, Optional +from typing import Any, Mapping, Optional from deployment.core.backend import Backend from deployment.core.evaluation.evaluator_types import ModelSpec @@ -22,7 +22,11 @@ @pipeline_registry.register class CenterPointPipelineFactory(BasePipelineFactory): - """Pipeline factory for CenterPoint across supported backends.""" + """Pipeline factory for CenterPoint across supported backends. + + Supports passing `components_cfg` to configure component file paths + and IO specifications. + """ @classmethod def get_project_name(cls) -> str: @@ -34,8 +38,22 @@ def create_pipeline( model_spec: ModelSpec, pytorch_model: Any, device: Optional[str] = None, + components_cfg: Optional[Mapping[str, Any]] = None, **kwargs, ) -> BaseDeploymentPipeline: + """Create a CenterPoint pipeline for the specified backend. + + Args: + model_spec: Model specification (backend/device/path) + pytorch_model: PyTorch model instance for preprocessing + device: Override device (uses model_spec.device if None) + components_cfg: Unified component configuration dict from deploy_config. + Used to configure component file paths. + **kwargs: Additional arguments (unused) + + Returns: + Pipeline instance for the specified backend + """ device = device or model_spec.device backend = model_spec.backend @@ -51,6 +69,7 @@ def create_pipeline( pytorch_model, onnx_dir=model_spec.path, device=device, + components_cfg=components_cfg, ) if backend is Backend.TENSORRT: @@ -59,6 +78,7 @@ def create_pipeline( pytorch_model, tensorrt_dir=model_spec.path, device=device, + components_cfg=components_cfg, ) raise ValueError(f"Unsupported backend: {backend.value}") diff --git a/deployment/projects/centerpoint/pipelines/onnx.py b/deployment/projects/centerpoint/pipelines/onnx.py index db4024a1a..673bb3d92 100644 --- a/deployment/projects/centerpoint/pipelines/onnx.py +++ b/deployment/projects/centerpoint/pipelines/onnx.py @@ -4,30 +4,58 @@ import logging import os.path as osp -from typing import List +from typing import Any, List, Mapping import numpy as np import onnxruntime as ort import torch +from deployment.projects.centerpoint.pipelines.artifacts import resolve_component_artifact_path from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline logger = logging.getLogger(__name__) class CenterPointONNXPipeline(CenterPointDeploymentPipeline): - """ONNXRuntime-based CenterPoint pipeline (componentized inference).""" - - def __init__(self, pytorch_model, onnx_dir: str, device: str = "cpu"): + """ONNXRuntime-based CenterPoint pipeline (componentized inference). + + Args: + pytorch_model: Reference PyTorch model for preprocessing + onnx_dir: Directory containing ONNX model files + device: Target device ('cpu' or 'cuda:N') + components_cfg: Component configuration dict from deploy_config. + If None, uses default component names. + """ + + def __init__( + self, + pytorch_model, + onnx_dir: str, + device: str = "cpu", + components_cfg: Mapping[str, Any] | None = None, + ): super().__init__(pytorch_model, device, backend_type="onnx") self.onnx_dir = onnx_dir + self._components_cfg = components_cfg or {} self._load_onnx_models(device) logger.info(f"ONNX pipeline initialized with models from: {onnx_dir}") def _load_onnx_models(self, device: str): - voxel_encoder_path = osp.join(self.onnx_dir, "pts_voxel_encoder.onnx") - backbone_head_path = osp.join(self.onnx_dir, "pts_backbone_neck_head.onnx") + voxel_encoder_path = resolve_component_artifact_path( + base_dir=self.onnx_dir, + components_cfg=self._components_cfg, + component="voxel_encoder", + file_key="onnx_file", + default_filename="pts_voxel_encoder.onnx", + ) + backbone_head_path = resolve_component_artifact_path( + base_dir=self.onnx_dir, + components_cfg=self._components_cfg, + component="backbone_head", + file_key="onnx_file", + default_filename="pts_backbone_neck_head.onnx", + ) if not osp.exists(voxel_encoder_path): raise FileNotFoundError(f"Voxel encoder ONNX not found: {voxel_encoder_path}") diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py index 00c452e0d..fd73b38fd 100644 --- a/deployment/projects/centerpoint/pipelines/tensorrt.py +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -4,7 +4,7 @@ import logging import os.path as osp -from typing import List +from typing import Any, List, Mapping import numpy as np import pycuda.autoinit # noqa: F401 @@ -17,22 +17,37 @@ TensorRTResourceManager, release_tensorrt_resources, ) -from deployment.projects.centerpoint.config.deploy_config import onnx_config +from deployment.projects.centerpoint.pipelines.artifacts import resolve_component_artifact_path from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline logger = logging.getLogger(__name__) class CenterPointTensorRTPipeline(GPUResourceMixin, CenterPointDeploymentPipeline): - """TensorRT-based CenterPoint pipeline (engine-per-component inference).""" - - def __init__(self, pytorch_model, tensorrt_dir: str, device: str = "cuda"): + """TensorRT-based CenterPoint pipeline (engine-per-component inference). + + Args: + pytorch_model: Reference PyTorch model for preprocessing + tensorrt_dir: Directory containing TensorRT engine files + device: Target device (must be 'cuda:N') + components_cfg: Component configuration dict from deploy_config. + If None, uses default component names. + """ + + def __init__( + self, + pytorch_model, + tensorrt_dir: str, + device: str = "cuda", + components_cfg: Mapping[str, Any] | None = None, + ): if not device.startswith("cuda"): raise ValueError("TensorRT requires CUDA device") super().__init__(pytorch_model, device, backend_type="tensorrt") self.tensorrt_dir = tensorrt_dir + self._components_cfg = components_cfg or {} self._engines = {} self._contexts = {} self._logger = trt.Logger(trt.Logger.WARNING) @@ -45,16 +60,24 @@ def _load_tensorrt_engines(self): trt.init_libnvinfer_plugins(self._logger, "") runtime = trt.Runtime(self._logger) - component_cfg = onnx_config.get("components", {}) - voxel_cfg = component_cfg.get("voxel_encoder", {}) - backbone_cfg = component_cfg.get("backbone_head", {}) engine_files = { - "voxel_encoder": voxel_cfg.get("engine_file", "pts_voxel_encoder.engine"), - "backbone_neck_head": backbone_cfg.get("engine_file", "pts_backbone_neck_head.engine"), + "voxel_encoder": resolve_component_artifact_path( + base_dir=self.tensorrt_dir, + components_cfg=self._components_cfg, + component="voxel_encoder", + file_key="engine_file", + default_filename="pts_voxel_encoder.engine", + ), + "backbone_head": resolve_component_artifact_path( + base_dir=self.tensorrt_dir, + components_cfg=self._components_cfg, + component="backbone_head", + file_key="engine_file", + default_filename="pts_backbone_neck_head.engine", + ), } - for component, engine_file in engine_files.items(): - engine_path = osp.join(self.tensorrt_dir, engine_file) + for component, engine_path in engine_files.items(): if not osp.exists(engine_path): raise FileNotFoundError(f"TensorRT engine not found: {engine_path}") @@ -128,10 +151,10 @@ def _get_io_names(self, engine, single_output: bool = False): return input_name, output_names def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: - engine = self._engines["backbone_neck_head"] - context = self._contexts["backbone_neck_head"] + engine = self._engines["backbone_head"] + context = self._contexts["backbone_head"] if context is None: - raise RuntimeError("backbone_neck_head context is None - likely failed to initialize due to GPU OOM") + raise RuntimeError("backbone_head context is None - likely failed to initialize due to GPU OOM") input_array = spatial_features.cpu().numpy().astype(np.float32) if not input_array.flags["C_CONTIGUOUS"]: From b52dc4f7fa2778535c52d1a7f4cca15c735deafe Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 7 Jan 2026 15:36:30 +0900 Subject: [PATCH 10/16] chore: clean code Signed-off-by: vividf --- deployment/projects/centerpoint/entrypoint.py | 17 +- .../projects/centerpoint/metrics_utils.py | 85 ++++++++ .../projects/centerpoint/model_loader.py | 111 ++++------ .../centerpoint/onnx_models/__init__.py | 44 ++-- .../pipelines/centerpoint_pipeline.py | 189 +++++++++++++++--- .../projects/centerpoint/pipelines/onnx.py | 64 +++++- .../projects/centerpoint/pipelines/pytorch.py | 63 +++++- .../centerpoint/pipelines/tensorrt.py | 131 ++++++++---- deployment/projects/centerpoint/runner.py | 93 +++++++-- 9 files changed, 614 insertions(+), 183 deletions(-) create mode 100644 deployment/projects/centerpoint/metrics_utils.py diff --git a/deployment/projects/centerpoint/entrypoint.py b/deployment/projects/centerpoint/entrypoint.py index 2fd6a7022..17f945b9d 100644 --- a/deployment/projects/centerpoint/entrypoint.py +++ b/deployment/projects/centerpoint/entrypoint.py @@ -2,24 +2,31 @@ from __future__ import annotations +import argparse import logging +from typing import Any, Mapping from mmengine.config import Config from deployment.core.config.base_config import BaseDeploymentConfig, setup_logging from deployment.core.contexts import CenterPointExportContext -from deployment.core.metrics.detection_3d_metrics import Detection3DMetricsConfig from deployment.projects.centerpoint.data_loader import CenterPointDataLoader from deployment.projects.centerpoint.evaluator import CenterPointEvaluator -from deployment.projects.centerpoint.model_loader import extract_t4metric_v2_config +from deployment.projects.centerpoint.metrics_utils import extract_t4metric_v2_config from deployment.projects.centerpoint.runner import CenterPointDeploymentRunner -def run(args) -> int: +def run(args: argparse.Namespace) -> int: """Run the CenterPoint deployment workflow for the unified CLI. This wires together the CenterPoint bundle components (data loader, evaluator, runner) and executes export/verification/evaluation according to `deploy_cfg`. + + Args: + args: Parsed command-line arguments containing deploy_cfg and model_cfg paths. + + Returns: + Exit code (0 for success). """ logger = setup_logging(args.log_level) @@ -27,6 +34,9 @@ def run(args) -> int: model_cfg = Config.fromfile(args.model_cfg) config = BaseDeploymentConfig(deploy_cfg) + # Extract components config for dependency injection + components_cfg: Mapping[str, Any] = deploy_cfg.get("components", {}) or {} + logger.info("=" * 80) logger.info("CenterPoint Deployment Pipeline (Unified CLI)") logger.info("=" * 80) @@ -44,6 +54,7 @@ def run(args) -> int: evaluator = CenterPointEvaluator( model_cfg=model_cfg, metrics_config=metrics_config, + components_cfg=components_cfg, ) runner = CenterPointDeploymentRunner( diff --git a/deployment/projects/centerpoint/metrics_utils.py b/deployment/projects/centerpoint/metrics_utils.py new file mode 100644 index 000000000..ad412fe82 --- /dev/null +++ b/deployment/projects/centerpoint/metrics_utils.py @@ -0,0 +1,85 @@ +""" +CenterPoint metrics utilities. + +This module extracts metrics configuration from MMEngine model configs. +""" + +import logging +from typing import List, Optional + +from mmengine.config import Config + +from deployment.core.metrics.detection_3d_metrics import Detection3DMetricsConfig + + +def extract_t4metric_v2_config( + model_cfg: Config, + class_names: Optional[List[str]] = None, + logger: Optional[logging.Logger] = None, +) -> Detection3DMetricsConfig: + """Extract `Detection3DMetricsConfig` from an MMEngine model config. + + Expects the config to contain a `T4MetricV2` evaluator (val or test). + + Args: + model_cfg: MMEngine model configuration. + class_names: Optional list of class names. If not provided, + extracted from model_cfg.class_names. + logger: Optional logger instance. + + Returns: + Detection3DMetricsConfig instance with extracted settings. + + Raises: + ValueError: If class_names not provided and not found in model_cfg, + or if evaluator config is missing or not T4MetricV2 type. + """ + if logger is None: + logger = logging.getLogger(__name__) + + if class_names is None: + if hasattr(model_cfg, "class_names"): + class_names = model_cfg.class_names + else: + raise ValueError("class_names must be provided or defined in model_cfg.class_names") + + evaluator_cfg = None + if hasattr(model_cfg, "val_evaluator"): + evaluator_cfg = model_cfg.val_evaluator + elif hasattr(model_cfg, "test_evaluator"): + evaluator_cfg = model_cfg.test_evaluator + else: + raise ValueError("No val_evaluator or test_evaluator found in model_cfg") + + def get_cfg_value(cfg, key, default=None): + if cfg is None: + return default + if isinstance(cfg, dict): + return cfg.get(key, default) + return getattr(cfg, key, default) + + evaluator_type = get_cfg_value(evaluator_cfg, "type") + if evaluator_type != "T4MetricV2": + raise ValueError(f"Evaluator type is '{evaluator_type}', not 'T4MetricV2'") + + perception_configs = get_cfg_value(evaluator_cfg, "perception_evaluator_configs", {}) + evaluation_config_dict = get_cfg_value(perception_configs, "evaluation_config_dict") + frame_id = get_cfg_value(perception_configs, "frame_id", "base_link") + + critical_object_filter_config = get_cfg_value(evaluator_cfg, "critical_object_filter_config") + frame_pass_fail_config = get_cfg_value(evaluator_cfg, "frame_pass_fail_config") + + if evaluation_config_dict and hasattr(evaluation_config_dict, "to_dict"): + evaluation_config_dict = dict(evaluation_config_dict) + if critical_object_filter_config and hasattr(critical_object_filter_config, "to_dict"): + critical_object_filter_config = dict(critical_object_filter_config) + if frame_pass_fail_config and hasattr(frame_pass_fail_config, "to_dict"): + frame_pass_fail_config = dict(frame_pass_fail_config) + + return Detection3DMetricsConfig( + class_names=class_names, + frame_id=frame_id, + evaluation_config_dict=evaluation_config_dict, + critical_object_filter_config=critical_object_filter_config, + frame_pass_fail_config=frame_pass_fail_config, + ) diff --git a/deployment/projects/centerpoint/model_loader.py b/deployment/projects/centerpoint/model_loader.py index cd91905b1..372338c23 100644 --- a/deployment/projects/centerpoint/model_loader.py +++ b/deployment/projects/centerpoint/model_loader.py @@ -1,17 +1,19 @@ """ -CenterPoint deployment utilities: ONNX-compatible model building and metrics config extraction. +CenterPoint model loading utilities. + +This module provides ONNX-compatible model building from MMEngine configs. """ +from __future__ import annotations + import copy -import logging -from typing import List, Optional, Tuple +from typing import Tuple import torch from mmengine.config import Config from mmengine.registry import MODELS, init_default_scope from mmengine.runner import load_checkpoint -from deployment.core.metrics.detection_3d_metrics import Detection3DMetricsConfig from deployment.projects.centerpoint.onnx_models import register_models @@ -24,6 +26,14 @@ def create_onnx_model_cfg( This mutates the `model_cfg.model` subtree to reference classes registered by `deployment.projects.centerpoint.onnx_models` (e.g., `CenterPointONNX`). + + Args: + model_cfg: Original MMEngine model configuration. + device: Target device string (e.g., 'cpu', 'cuda:0'). + rot_y_axis_reference: Whether to use y-axis rotation reference. + + Returns: + Modified config with ONNX-compatible model types. """ onnx_cfg = model_cfg.copy() model_config = copy.deepcopy(onnx_cfg.model) @@ -51,12 +61,25 @@ def create_onnx_model_cfg( return onnx_cfg -def build_model_from_cfg(model_cfg: Config, checkpoint_path: str, device: str) -> torch.nn.Module: - """Build a model from MMEngine config and load checkpoint weights.""" +def build_model_from_cfg( + model_cfg: Config, + checkpoint_path: str, + device: str, +) -> torch.nn.Module: + """Build a model from MMEngine config and load checkpoint weights. + + Args: + model_cfg: MMEngine model configuration. + checkpoint_path: Path to the checkpoint file. + device: Target device string. + + Returns: + Loaded and initialized PyTorch model in eval mode. + """ # Ensure CenterPoint ONNX variants are registered into MODELS before building. - # This is required because the config uses string types like "CenterPointONNX", "CenterHeadONNX", etc. register_models() init_default_scope("mmdet3d") + model_config = copy.deepcopy(model_cfg.model) model = MODELS.build(model_config) model.to(device) @@ -72,7 +95,19 @@ def build_centerpoint_onnx_model( device: str, rot_y_axis_reference: bool = False, ) -> Tuple[torch.nn.Module, Config]: - """Convenience wrapper to build an ONNX-compatible CenterPoint model + cfg.""" + """Build an ONNX-compatible CenterPoint model. + + Convenience wrapper that creates ONNX config and builds the model. + + Args: + base_model_cfg: Base MMEngine model configuration. + checkpoint_path: Path to the checkpoint file. + device: Target device string. + rot_y_axis_reference: Whether to use y-axis rotation reference. + + Returns: + Tuple of (model, onnx_compatible_config). + """ onnx_cfg = create_onnx_model_cfg( base_model_cfg, device=device, @@ -80,63 +115,3 @@ def build_centerpoint_onnx_model( ) model = build_model_from_cfg(onnx_cfg, checkpoint_path, device=device) return model, onnx_cfg - - -def extract_t4metric_v2_config( - model_cfg: Config, - class_names: Optional[List[str]] = None, - logger: Optional[logging.Logger] = None, -) -> Detection3DMetricsConfig: - """Extract `Detection3DMetricsConfig` from an MMEngine model config. - - Expects the config to contain a `T4MetricV2` evaluator (val or test). - """ - if logger is None: - logger = logging.getLogger(__name__) - - if class_names is None: - if hasattr(model_cfg, "class_names"): - class_names = model_cfg.class_names - else: - raise ValueError("class_names must be provided or defined in model_cfg.class_names") - - evaluator_cfg = None - if hasattr(model_cfg, "val_evaluator"): - evaluator_cfg = model_cfg.val_evaluator - elif hasattr(model_cfg, "test_evaluator"): - evaluator_cfg = model_cfg.test_evaluator - else: - raise ValueError("No val_evaluator or test_evaluator found in model_cfg") - - def get_cfg_value(cfg, key, default=None): - if cfg is None: - return default - if isinstance(cfg, dict): - return cfg.get(key, default) - return getattr(cfg, key, default) - - evaluator_type = get_cfg_value(evaluator_cfg, "type") - if evaluator_type != "T4MetricV2": - raise ValueError(f"Evaluator type is '{evaluator_type}', not 'T4MetricV2'") - - perception_configs = get_cfg_value(evaluator_cfg, "perception_evaluator_configs", {}) - evaluation_config_dict = get_cfg_value(perception_configs, "evaluation_config_dict") - frame_id = get_cfg_value(perception_configs, "frame_id", "base_link") - - critical_object_filter_config = get_cfg_value(evaluator_cfg, "critical_object_filter_config") - frame_pass_fail_config = get_cfg_value(evaluator_cfg, "frame_pass_fail_config") - - if evaluation_config_dict and hasattr(evaluation_config_dict, "to_dict"): - evaluation_config_dict = dict(evaluation_config_dict) - if critical_object_filter_config and hasattr(critical_object_filter_config, "to_dict"): - critical_object_filter_config = dict(critical_object_filter_config) - if frame_pass_fail_config and hasattr(frame_pass_fail_config, "to_dict"): - frame_pass_fail_config = dict(frame_pass_fail_config) - - return Detection3DMetricsConfig( - class_names=class_names, - frame_id=frame_id, - evaluation_config_dict=evaluation_config_dict, - critical_object_filter_config=critical_object_filter_config, - frame_pass_fail_config=frame_pass_fail_config, - ) diff --git a/deployment/projects/centerpoint/onnx_models/__init__.py b/deployment/projects/centerpoint/onnx_models/__init__.py index 94e04a288..40f39ffb6 100644 --- a/deployment/projects/centerpoint/onnx_models/__init__.py +++ b/deployment/projects/centerpoint/onnx_models/__init__.py @@ -1,28 +1,42 @@ -"""CenterPoint deploy-only ONNX model definitions. +"""CenterPoint ONNX-compatible model definitions. -These modules exist to support ONNX export / ONNX-friendly execution graphs. -They are registered into MMEngine's `MODELS` registry via import side-effects -(`@MODELS.register_module()`). +This module contains model variants that support ONNX export: -Important: -- Call `register_models()` before building models that reference types like - "CenterPointONNX", "CenterHeadONNX", "SeparateHeadONNX", - "PillarFeatureNetONNX", "BackwardPillarFeatureNetONNX". +- ``CenterPointONNX``: ONNX-compatible detector with feature extraction helpers. +- ``CenterHeadONNX``: ONNX-compatible detection head with stable output ordering. +- ``SeparateHeadONNX``: ONNX-compatible separate head with deterministic ordering. +- ``PillarFeatureNetONNX``: ONNX-compatible pillar feature network. +- ``BackwardPillarFeatureNetONNX``: Backward-compatible pillar feature network. + +**Note**: These are model *definitions* for ONNX export, not exported model artifacts. +They are registered into MMEngine's ``MODELS`` registry via ``@MODELS.register_module()``. + +Usage: + Call ``register_models()`` before building models that reference types like + "CenterPointONNX", "CenterHeadONNX", etc. + +Example: + >>> from deployment.projects.centerpoint.onnx_models import register_models + >>> register_models() # Register ONNX model variants + >>> # Now you can build models with type="CenterPointONNX" in config """ from __future__ import annotations def register_models() -> None: - """Register CenterPoint ONNX model variants into MMEngine's `MODELS` registry. + """Register CenterPoint ONNX model variants into MMEngine's MODELS registry. + + Importing the submodules triggers ``@MODELS.register_module()`` decorators, + which registers the types referenced by config strings (e.g., "CenterPointONNX"). - The underlying modules use `@MODELS.register_module()`; importing them is enough - to register the types referenced by config strings (e.g., `CenterPointONNX`). + This function should be called before ``MODELS.build()`` for configs that + use ONNX model variants. """ - # Importing modules triggers `@MODELS.register_module()` registrations. - from deployment.projects.centerpoint.onnx_models import centerpoint_head_onnx as _ # noqa: F401 - from deployment.projects.centerpoint.onnx_models import centerpoint_onnx as _ # noqa: F401 - from deployment.projects.centerpoint.onnx_models import pillar_encoder_onnx as _ # noqa: F401 + # Import triggers @MODELS.register_module() registrations + from deployment.projects.centerpoint.onnx_models import centerpoint_head_onnx as _head # noqa: F401 + from deployment.projects.centerpoint.onnx_models import centerpoint_onnx as _model # noqa: F401 + from deployment.projects.centerpoint.onnx_models import pillar_encoder_onnx as _encoder # noqa: F401 __all__ = ["register_models"] diff --git a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py index 331913448..4355ac3be 100644 --- a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py +++ b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py @@ -1,13 +1,18 @@ """ CenterPoint Deployment Pipeline Base Class. +Provides common preprocessing, postprocessing, and inference logic +shared by PyTorch, ONNX, and TensorRT backend implementations. """ +from __future__ import annotations + import logging import time from abc import abstractmethod -from typing import Dict, List, Tuple +from typing import Any, Dict, List, Optional, Tuple, Union +import numpy as np import torch from mmdet3d.structures import Det3DDataSample, LiDARInstance3DBoxes @@ -22,9 +27,31 @@ class CenterPointDeploymentPipeline(BaseDeploymentPipeline): This normalizes preprocessing/postprocessing for CenterPoint and provides common helpers (e.g., middle encoder processing) used by PyTorch/ONNX/TensorRT backend-specific pipelines. + + Attributes: + pytorch_model: Reference PyTorch model for preprocessing/postprocessing. + num_classes: Number of detection classes. + class_names: List of class names. + point_cloud_range: Point cloud range [x_min, y_min, z_min, x_max, y_max, z_max]. + voxel_size: Voxel size [vx, vy, vz]. """ - def __init__(self, pytorch_model, device: str = "cuda", backend_type: str = "unknown"): + def __init__( + self, + pytorch_model: torch.nn.Module, + device: str = "cuda", + backend_type: str = "unknown", + ) -> None: + """Initialize CenterPoint pipeline. + + Args: + pytorch_model: PyTorch model for preprocessing/postprocessing. + device: Target device ('cpu' or 'cuda:N'). + backend_type: Backend identifier ('pytorch', 'onnx', 'tensorrt'). + + Raises: + ValueError: If class_names not found in pytorch_model.cfg. + """ cfg = getattr(pytorch_model, "cfg", None) class_names = getattr(cfg, "class_names", None) @@ -41,15 +68,60 @@ def __init__(self, pytorch_model, device: str = "cuda", backend_type: str = "unk backend_type=backend_type, ) - self.num_classes = len(class_names) - self.class_names = class_names - self.point_cloud_range = point_cloud_range - self.voxel_size = voxel_size - self.pytorch_model = pytorch_model - self._stage_latencies = {} - - def preprocess(self, points: torch.Tensor, **kwargs) -> Tuple[Dict[str, torch.Tensor], Dict]: - points_tensor = points.to(self.device) + self.num_classes: int = len(class_names) + self.class_names: List[str] = class_names + self.point_cloud_range: Optional[List[float]] = point_cloud_range + self.voxel_size: Optional[List[float]] = voxel_size + self.pytorch_model: torch.nn.Module = pytorch_model + self._stage_latencies: Dict[str, float] = {} + + def to_device_tensor(self, data: Union[torch.Tensor, np.ndarray]) -> torch.Tensor: + """Convert data to tensor on the pipeline's device. + + Args: + data: Input data (torch.Tensor or np.ndarray). + + Returns: + Tensor on self.device. + """ + if isinstance(data, np.ndarray): + data = torch.from_numpy(data) + return data.to(self.device) + + def to_numpy(self, data: torch.Tensor, dtype: np.dtype = np.float32) -> np.ndarray: + """Convert tensor to contiguous numpy array. + + Args: + data: Input tensor. + dtype: Target numpy dtype. + + Returns: + Contiguous numpy array. + """ + arr = data.cpu().numpy().astype(dtype) + if not arr.flags["C_CONTIGUOUS"]: + arr = np.ascontiguousarray(arr) + return arr + + def preprocess( + self, + points: torch.Tensor, + **kwargs: Any, + ) -> Tuple[Dict[str, torch.Tensor], Dict[str, Any]]: + """Preprocess point cloud data for inference. + + Performs voxelization and feature extraction using the data_preprocessor + and pts_voxel_encoder from the PyTorch model. + + Args: + points: Point cloud tensor of shape [N, point_features]. + **kwargs: Additional arguments (unused). + + Returns: + Tuple of (preprocessed_dict, metadata_dict). + preprocessed_dict contains: input_features, voxels, num_points, coors. + """ + points_tensor = self.to_device_tensor(points) data_samples = [Det3DDataSample()] with torch.no_grad(): @@ -62,7 +134,7 @@ def preprocess(self, points: torch.Tensor, **kwargs) -> Tuple[Dict[str, torch.Te num_points = voxel_dict["num_points"] coors = voxel_dict["coors"] - input_features = None + input_features: Optional[torch.Tensor] = None with torch.no_grad(): if hasattr(self.pytorch_model.pts_voxel_encoder, "get_input_features"): input_features = self.pytorch_model.pts_voxel_encoder.get_input_features(voxels, num_points, coors) @@ -76,21 +148,58 @@ def preprocess(self, points: torch.Tensor, **kwargs) -> Tuple[Dict[str, torch.Te return preprocessed_dict, {} - def process_middle_encoder(self, voxel_features: torch.Tensor, coors: torch.Tensor) -> torch.Tensor: - voxel_features = voxel_features.to(self.device) - coors = coors.to(self.device) + def process_middle_encoder( + self, + voxel_features: torch.Tensor, + coors: torch.Tensor, + ) -> torch.Tensor: + """Process voxel features through middle encoder (scatter to BEV). + + This step runs on PyTorch regardless of backend because it involves + sparse-to-dense conversion that's not easily exportable to ONNX. + + Args: + voxel_features: Encoded voxel features [N, feature_dim]. + coors: Voxel coordinates [N, 4] (batch_idx, z, y, x). + + Returns: + Spatial features tensor [B, C, H, W]. + """ + voxel_features = self.to_device_tensor(voxel_features) + coors = self.to_device_tensor(coors) + batch_size = int(coors[-1, 0].item()) + 1 if len(coors) > 0 else 1 + with torch.no_grad(): spatial_features = self.pytorch_model.pts_middle_encoder(voxel_features, coors, batch_size) + return spatial_features - def postprocess(self, head_outputs: List[torch.Tensor], sample_meta: Dict) -> List[Dict]: - head_outputs = [out.to(self.device) for out in head_outputs] + def postprocess( + self, + head_outputs: List[torch.Tensor], + sample_meta: Dict[str, Any], + ) -> List[Dict[str, Any]]: + """Postprocess head outputs to detection results. + + Args: + head_outputs: List of 6 tensors [heatmap, reg, height, dim, rot, vel]. + sample_meta: Sample metadata dict. + + Returns: + List of detection dicts with keys: bbox_3d, score, label. + + Raises: + ValueError: If head_outputs doesn't contain exactly 6 tensors. + """ + head_outputs = [self.to_device_tensor(out) for out in head_outputs] + if len(head_outputs) != 6: raise ValueError(f"Expected 6 head outputs, got {len(head_outputs)}") heatmap, reg, height, dim, rot, vel = head_outputs + # Apply rotation axis correction if configured if hasattr(self.pytorch_model, "pts_bbox_head"): rot_y_axis_reference = getattr(self.pytorch_model.pts_bbox_head, "_rot_y_axis_reference", False) if rot_y_axis_reference: @@ -98,7 +207,14 @@ def postprocess(self, head_outputs: List[torch.Tensor], sample_meta: Dict) -> Li rot = rot * (-1.0) rot = rot[:, [1, 0], :, :] - preds_dict = {"heatmap": heatmap, "reg": reg, "height": height, "dim": dim, "rot": rot, "vel": vel} + preds_dict = { + "heatmap": heatmap, + "reg": reg, + "height": height, + "dim": dim, + "rot": rot, + "vel": vel, + } preds_dicts = ([preds_dict],) if "box_type_3d" not in sample_meta: @@ -110,7 +226,7 @@ def postprocess(self, head_outputs: List[torch.Tensor], sample_meta: Dict) -> Li preds_dicts=preds_dicts, batch_input_metas=batch_input_metas ) - results = [] + results: List[Dict[str, Any]] = [] for pred_instances in predictions_list: bboxes_3d = pred_instances.bboxes_3d.tensor.cpu().numpy() scores_3d = pred_instances.scores_3d.cpu().numpy() @@ -129,14 +245,41 @@ def postprocess(self, head_outputs: List[torch.Tensor], sample_meta: Dict) -> Li @abstractmethod def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + """Run voxel encoder inference. + + Args: + input_features: Input features [N, max_points, C]. + + Returns: + Voxel features [N, feature_dim]. + """ raise NotImplementedError @abstractmethod def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + """Run backbone and head inference. + + Args: + spatial_features: Spatial features [B, C, H, W]. + + Returns: + List of 6 head output tensors. + """ raise NotImplementedError - def run_model(self, preprocessed_input: Dict[str, torch.Tensor]) -> Tuple[List[torch.Tensor], Dict[str, float]]: - stage_latencies = {} + def run_model( + self, + preprocessed_input: Dict[str, torch.Tensor], + ) -> Tuple[List[torch.Tensor], Dict[str, float]]: + """Run the full model pipeline with latency tracking. + + Args: + preprocessed_input: Dict with keys: input_features, coors. + + Returns: + Tuple of (head_outputs, stage_latencies). + """ + stage_latencies: Dict[str, float] = {} start = time.perf_counter() voxel_features = self.run_voxel_encoder(preprocessed_input["input_features"]) @@ -152,5 +295,5 @@ def run_model(self, preprocessed_input: Dict[str, torch.Tensor]) -> Tuple[List[t return head_outputs, stage_latencies - def __repr__(self): - return f"{self.__class__.__name__}(device={self.device})" + def __repr__(self) -> str: + return f"{self.__class__.__name__}(device={self.device}, backend={self.backend_type})" diff --git a/deployment/projects/centerpoint/pipelines/onnx.py b/deployment/projects/centerpoint/pipelines/onnx.py index 673bb3d92..f43177512 100644 --- a/deployment/projects/centerpoint/pipelines/onnx.py +++ b/deployment/projects/centerpoint/pipelines/onnx.py @@ -2,6 +2,8 @@ CenterPoint ONNX Pipeline Implementation. """ +from __future__ import annotations + import logging import os.path as osp from typing import Any, List, Mapping @@ -19,21 +21,31 @@ class CenterPointONNXPipeline(CenterPointDeploymentPipeline): """ONNXRuntime-based CenterPoint pipeline (componentized inference). - Args: - pytorch_model: Reference PyTorch model for preprocessing - onnx_dir: Directory containing ONNX model files - device: Target device ('cpu' or 'cuda:N') - components_cfg: Component configuration dict from deploy_config. - If None, uses default component names. + Loads separate ONNX models for voxel_encoder and backbone_head components + and runs inference using ONNXRuntime. + + Attributes: + onnx_dir: Directory containing ONNX model files. + voxel_encoder_session: ONNXRuntime session for voxel encoder. + backbone_head_session: ONNXRuntime session for backbone + head. """ def __init__( self, - pytorch_model, + pytorch_model: torch.nn.Module, onnx_dir: str, device: str = "cpu", components_cfg: Mapping[str, Any] | None = None, - ): + ) -> None: + """Initialize ONNX pipeline. + + Args: + pytorch_model: Reference PyTorch model for preprocessing. + onnx_dir: Directory containing ONNX model files. + device: Target device ('cpu' or 'cuda:N'). + components_cfg: Component configuration dict from deploy_config. + If None, uses default component names. + """ super().__init__(pytorch_model, device, backend_type="onnx") self.onnx_dir = onnx_dir @@ -41,7 +53,16 @@ def __init__( self._load_onnx_models(device) logger.info(f"ONNX pipeline initialized with models from: {onnx_dir}") - def _load_onnx_models(self, device: str): + def _load_onnx_models(self, device: str) -> None: + """Load ONNX models for each component. + + Args: + device: Target device for execution provider selection. + + Raises: + FileNotFoundError: If ONNX model files are not found. + RuntimeError: If model loading fails. + """ voxel_encoder_path = resolve_component_artifact_path( base_dir=self.onnx_dir, components_cfg=self._components_cfg, @@ -62,10 +83,12 @@ def _load_onnx_models(self, device: str): if not osp.exists(backbone_head_path): raise FileNotFoundError(f"Backbone head ONNX not found: {backbone_head_path}") + # Configure session options so = ort.SessionOptions() so.graph_optimization_level = ort.GraphOptimizationLevel.ORT_DISABLE_ALL so.log_severity_level = 3 + # Select execution providers based on device if device.startswith("cuda"): providers = ["CUDAExecutionProvider", "CPUExecutionProvider"] logger.info("Using CUDA execution provider for ONNX") @@ -86,7 +109,15 @@ def _load_onnx_models(self, device: str): raise RuntimeError(f"Failed to load backbone+head ONNX: {e}") def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: - input_array = input_features.cpu().numpy().astype(np.float32) + """Run voxel encoder using ONNXRuntime. + + Args: + input_features: Input features [N, max_points, C]. + + Returns: + Voxel features [N, feature_dim]. + """ + input_array = self.to_numpy(input_features, dtype=np.float32) input_name = self.voxel_encoder_session.get_inputs()[0].name output_name = self.voxel_encoder_session.get_outputs()[0].name @@ -98,7 +129,18 @@ def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: return voxel_features def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: - input_array = spatial_features.cpu().numpy().astype(np.float32) + """Run backbone and head using ONNXRuntime. + + Args: + spatial_features: Spatial features [B, C, H, W]. + + Returns: + List of 6 head output tensors. + + Raises: + ValueError: If output count is not 6. + """ + input_array = self.to_numpy(spatial_features, dtype=np.float32) input_name = self.backbone_head_session.get_inputs()[0].name output_names = [output.name for output in self.backbone_head_session.get_outputs()] diff --git a/deployment/projects/centerpoint/pipelines/pytorch.py b/deployment/projects/centerpoint/pipelines/pytorch.py index ed31c7dd1..a3ddff528 100644 --- a/deployment/projects/centerpoint/pipelines/pytorch.py +++ b/deployment/projects/centerpoint/pipelines/pytorch.py @@ -2,8 +2,10 @@ CenterPoint PyTorch Pipeline Implementation. """ +from __future__ import annotations + import logging -from typing import Dict, List +from typing import Any, Dict, List, Optional import torch @@ -13,26 +15,64 @@ class CenterPointPyTorchPipeline(CenterPointDeploymentPipeline): - """PyTorch-based CenterPoint pipeline (staged to match ONNX/TensorRT outputs).""" + """PyTorch-based CenterPoint pipeline (staged to match ONNX/TensorRT outputs). + + This pipeline runs inference using the native PyTorch model, but structures + the execution to match the ONNX/TensorRT staged inference for consistency. + """ + + def __init__(self, pytorch_model: torch.nn.Module, device: str = "cuda") -> None: + """Initialize PyTorch pipeline. - def __init__(self, pytorch_model, device: str = "cuda"): + Args: + pytorch_model: PyTorch model for inference. + device: Target device ('cpu' or 'cuda:N'). + """ super().__init__(pytorch_model, device, backend_type="pytorch") logger.info("PyTorch pipeline initialized (ONNX-compatible staged inference)") - def infer(self, points: torch.Tensor, sample_meta: Dict = None, return_raw_outputs: bool = False): + def infer( + self, + points: torch.Tensor, + sample_meta: Optional[Dict[str, Any]] = None, + return_raw_outputs: bool = False, + ) -> Any: + """Run inference on point cloud. + + Args: + points: Point cloud tensor [N, point_features]. + sample_meta: Optional sample metadata. + return_raw_outputs: Whether to return raw outputs. + + Returns: + Detection results or raw outputs. + """ if sample_meta is None: sample_meta = {} return super().infer(points, sample_meta, return_raw_outputs=return_raw_outputs) def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + """Run voxel encoder using PyTorch model. + + Args: + input_features: Input features [N, max_points, C]. + + Returns: + Voxel features [N, feature_dim]. + + Raises: + ValueError: If input_features is None. + RuntimeError: If output shape is unexpected. + """ if input_features is None: raise ValueError("input_features is None. This should not happen for ONNX models.") - input_features = input_features.to(self.device) + input_features = self.to_device_tensor(input_features) with torch.no_grad(): voxel_features = self.pytorch_model.pts_voxel_encoder(input_features) + # Handle various output shapes from different encoder variants if voxel_features.ndim == 3: if voxel_features.shape[1] == 1: voxel_features = voxel_features.squeeze(1) @@ -52,7 +92,18 @@ def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: return voxel_features def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: - spatial_features = spatial_features.to(self.device) + """Run backbone and head using PyTorch model. + + Args: + spatial_features: Spatial features [B, C, H, W]. + + Returns: + List of 6 head output tensors. + + Raises: + ValueError: If head output format is unexpected. + """ + spatial_features = self.to_device_tensor(spatial_features) with torch.no_grad(): x = self.pytorch_model.pts_backbone(spatial_features) diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py index fd73b38fd..5d8acaefe 100644 --- a/deployment/projects/centerpoint/pipelines/tensorrt.py +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -2,9 +2,11 @@ CenterPoint TensorRT Pipeline Implementation. """ +from __future__ import annotations + import logging import os.path as osp -from typing import Any, List, Mapping +from typing import Any, List, Mapping, Tuple import numpy as np import pycuda.autoinit # noqa: F401 @@ -26,21 +28,32 @@ class CenterPointTensorRTPipeline(GPUResourceMixin, CenterPointDeploymentPipeline): """TensorRT-based CenterPoint pipeline (engine-per-component inference). - Args: - pytorch_model: Reference PyTorch model for preprocessing - tensorrt_dir: Directory containing TensorRT engine files - device: Target device (must be 'cuda:N') - components_cfg: Component configuration dict from deploy_config. - If None, uses default component names. + Loads separate TensorRT engines for voxel_encoder and backbone_head components + and runs inference using TensorRT execution contexts. + + Attributes: + tensorrt_dir: Directory containing TensorRT engine files. """ def __init__( self, - pytorch_model, + pytorch_model: torch.nn.Module, tensorrt_dir: str, device: str = "cuda", components_cfg: Mapping[str, Any] | None = None, - ): + ) -> None: + """Initialize TensorRT pipeline. + + Args: + pytorch_model: Reference PyTorch model for preprocessing. + tensorrt_dir: Directory containing TensorRT engine files. + device: Target CUDA device ('cuda:N'). + components_cfg: Component configuration dict from deploy_config. + If None, uses default component names. + + Raises: + ValueError: If device is not a CUDA device. + """ if not device.startswith("cuda"): raise ValueError("TensorRT requires CUDA device") @@ -48,15 +61,21 @@ def __init__( self.tensorrt_dir = tensorrt_dir self._components_cfg = components_cfg or {} - self._engines = {} - self._contexts = {} + self._engines: dict = {} + self._contexts: dict = {} self._logger = trt.Logger(trt.Logger.WARNING) self._cleanup_called = False self._load_tensorrt_engines() logger.info(f"TensorRT pipeline initialized with engines from: {tensorrt_dir}") - def _load_tensorrt_engines(self): + def _load_tensorrt_engines(self) -> None: + """Load TensorRT engines for each component. + + Raises: + FileNotFoundError: If engine files are not found. + RuntimeError: If engine loading or context creation fails. + """ trt.init_libnvinfer_plugins(self._logger, "") runtime = trt.Runtime(self._logger) @@ -89,22 +108,67 @@ def _load_tensorrt_engines(self): context = engine.create_execution_context() if context is None: raise RuntimeError( - f"Failed to create execution context for {component}. This is likely due to GPU out-of-memory." + f"Failed to create execution context for {component}. " "This is likely due to GPU out-of-memory." ) self._engines[component] = engine self._contexts[component] = context logger.info(f"Loaded TensorRT engine: {component}") + def _get_io_names( + self, + engine: Any, + single_output: bool = False, + ) -> Tuple[str, Any]: + """Get input and output tensor names from engine. + + Args: + engine: TensorRT engine. + single_output: If True, return single output name instead of list. + + Returns: + Tuple of (input_name, output_name(s)). + + Raises: + RuntimeError: If input or output names cannot be found. + """ + input_name = None + output_names = [] + + for i in range(engine.num_io_tensors): + tensor_name = engine.get_tensor_name(i) + if engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.INPUT: + input_name = tensor_name + elif engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.OUTPUT: + output_names.append(tensor_name) + + if input_name is None: + raise RuntimeError("Could not find input tensor name") + if not output_names: + raise RuntimeError("Could not find output tensor names") + + if single_output: + return input_name, output_names[0] + return input_name, output_names + def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: + """Run voxel encoder using TensorRT. + + Args: + input_features: Input features [N, max_points, C]. + + Returns: + Voxel features [N, feature_dim]. + + Raises: + RuntimeError: If context is None (initialization failed). + """ engine = self._engines["voxel_encoder"] context = self._contexts["voxel_encoder"] if context is None: raise RuntimeError("voxel_encoder context is None - likely failed to initialize due to GPU OOM") - input_array = input_features.cpu().numpy().astype(np.float32) - if not input_array.flags["C_CONTIGUOUS"]: - input_array = np.ascontiguousarray(input_array) + input_array = self.to_numpy(input_features, dtype=np.float32) input_name, output_name = self._get_io_names(engine, single_output=True) context.set_input_shape(input_name, input_array.shape) @@ -130,35 +194,25 @@ def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: voxel_features = voxel_features.squeeze(1) return voxel_features - def _get_io_names(self, engine, single_output: bool = False): - input_name = None - output_names = [] - - for i in range(engine.num_io_tensors): - tensor_name = engine.get_tensor_name(i) - if engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.INPUT: - input_name = tensor_name - elif engine.get_tensor_mode(tensor_name) == trt.TensorIOMode.OUTPUT: - output_names.append(tensor_name) + def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + """Run backbone and head using TensorRT. - if input_name is None: - raise RuntimeError("Could not find input tensor name") - if not output_names: - raise RuntimeError("Could not find output tensor names") + Args: + spatial_features: Spatial features [B, C, H, W]. - if single_output: - return input_name, output_names[0] - return input_name, output_names + Returns: + List of 6 head output tensors. - def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor]: + Raises: + RuntimeError: If context is None (initialization failed). + ValueError: If output count is not 6. + """ engine = self._engines["backbone_head"] context = self._contexts["backbone_head"] if context is None: raise RuntimeError("backbone_head context is None - likely failed to initialize due to GPU OOM") - input_array = spatial_features.cpu().numpy().astype(np.float32) - if not input_array.flags["C_CONTIGUOUS"]: - input_array = np.ascontiguousarray(input_array) + input_array = self.to_numpy(spatial_features, dtype=np.float32) input_name, output_names = self._get_io_names(engine, single_output=False) context.set_input_shape(input_name, input_array.shape) @@ -188,11 +242,14 @@ def run_backbone_head(self, spatial_features: torch.Tensor) -> List[torch.Tensor manager.synchronize() head_outputs = [torch.from_numpy(output_arrays[name]).to(self.device) for name in output_names] + if len(head_outputs) != 6: raise ValueError(f"Expected 6 head outputs, got {len(head_outputs)}") + return head_outputs def _release_gpu_resources(self) -> None: + """Release TensorRT resources (engines and contexts).""" release_tensorrt_resources( engines=getattr(self, "_engines", None), contexts=getattr(self, "_contexts", None), diff --git a/deployment/projects/centerpoint/runner.py b/deployment/projects/centerpoint/runner.py index ca2273b89..217767070 100644 --- a/deployment/projects/centerpoint/runner.py +++ b/deployment/projects/centerpoint/runner.py @@ -5,11 +5,18 @@ from __future__ import annotations import logging -from typing import Any +from typing import Any, Optional +import torch +from mmengine.config import Config + +from deployment.core import BaseDeploymentConfig from deployment.core.contexts import CenterPointExportContext, ExportContext +from deployment.core.io.base_data_loader import BaseDataLoader from deployment.exporters.common.factory import ExporterFactory from deployment.exporters.common.model_wrappers import IdentityWrapper +from deployment.exporters.export_pipelines.base import OnnxExportPipeline, TensorRTExportPipeline +from deployment.projects.centerpoint.evaluator import CenterPointEvaluator from deployment.projects.centerpoint.export.component_extractor import CenterPointComponentExtractor from deployment.projects.centerpoint.export.onnx_export_pipeline import CenterPointONNXExportPipeline from deployment.projects.centerpoint.export.tensorrt_export_pipeline import CenterPointTensorRTExportPipeline @@ -22,18 +29,33 @@ class CenterPointDeploymentRunner(BaseDeploymentRunner): Implements project-specific model loading and wiring to export pipelines, while reusing the project-agnostic orchestration in `BaseDeploymentRunner`. + + Attributes: + model_cfg: MMEngine model configuration. + evaluator: CenterPoint evaluator instance. """ def __init__( self, - data_loader, - evaluator, - config, - model_cfg, + data_loader: BaseDataLoader, + evaluator: CenterPointEvaluator, + config: BaseDeploymentConfig, + model_cfg: Config, logger: logging.Logger, - onnx_pipeline=None, - tensorrt_pipeline=None, - ): + onnx_pipeline: Optional[OnnxExportPipeline] = None, + tensorrt_pipeline: Optional[TensorRTExportPipeline] = None, + ) -> None: + """Initialize CenterPoint deployment runner. + + Args: + data_loader: Data loader for loading samples. + evaluator: Evaluator for computing metrics. + config: Deployment configuration. + model_cfg: MMEngine model configuration. + logger: Logger instance. + onnx_pipeline: Optional custom ONNX export pipeline. + tensorrt_pipeline: Optional custom TensorRT export pipeline. + """ component_extractor = CenterPointComponentExtractor(config=config, logger=logger) super().__init__( @@ -60,12 +82,17 @@ def __init__( logger=self.logger, ) - def load_pytorch_model(self, checkpoint_path: str, context: ExportContext) -> Any: - rot_y_axis_reference: bool = False - if isinstance(context, CenterPointExportContext): - rot_y_axis_reference = context.rot_y_axis_reference - else: - rot_y_axis_reference = context.get("rot_y_axis_reference", False) + def load_pytorch_model(self, checkpoint_path: str, context: ExportContext) -> torch.nn.Module: + """Load PyTorch model for export. + + Args: + checkpoint_path: Path to the checkpoint file. + context: Export context with additional parameters. + + Returns: + Loaded PyTorch model. + """ + rot_y_axis_reference = self._extract_rot_y_axis_reference(context) model, onnx_cfg = build_centerpoint_onnx_model( base_model_cfg=self.model_cfg, @@ -74,21 +101,47 @@ def load_pytorch_model(self, checkpoint_path: str, context: ExportContext) -> An rot_y_axis_reference=rot_y_axis_reference, ) + # Update model_cfg with ONNX-compatible version self.model_cfg = onnx_cfg - self._inject_model_to_evaluator(model, onnx_cfg) + + # Notify evaluator of model availability + self._setup_evaluator(model, onnx_cfg) + return model - def _inject_model_to_evaluator(self, model: Any, onnx_cfg: Any) -> None: + def _extract_rot_y_axis_reference(self, context: ExportContext) -> bool: + """Extract rot_y_axis_reference from export context. + + Args: + context: Export context (typed or dict-like). + + Returns: + Boolean value for rot_y_axis_reference. + """ + if isinstance(context, CenterPointExportContext): + return context.rot_y_axis_reference + return context.get("rot_y_axis_reference", False) + + def _setup_evaluator(self, model: torch.nn.Module, onnx_cfg: Config) -> None: + """Setup evaluator with loaded model and config. + + This method updates the evaluator with the PyTorch model and + ONNX-compatible configuration needed for evaluation. + + Args: + model: Loaded PyTorch model. + onnx_cfg: ONNX-compatible model configuration. + """ try: self.evaluator.set_onnx_config(onnx_cfg) - self.logger.info("Injected ONNX-compatible config to evaluator") + self.logger.info("Updated evaluator with ONNX-compatible config") except Exception as e: - self.logger.error(f"Failed to inject ONNX config: {e}") + self.logger.error(f"Failed to update evaluator config: {e}") raise try: self.evaluator.set_pytorch_model(model) - self.logger.info("Injected PyTorch model to evaluator") + self.logger.info("Updated evaluator with PyTorch model") except Exception as e: - self.logger.error(f"Failed to inject PyTorch model: {e}") + self.logger.error(f"Failed to set PyTorch model on evaluator: {e}") raise From ec9e97f1f1406c42862d352539594e3ecc535037 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 8 Jan 2026 17:05:14 +0900 Subject: [PATCH 11/16] chore: integrate centerpoint with new component structure Signed-off-by: vividf --- deployment/core/__init__.py | 12 +- deployment/core/artifacts.py | 256 +++++++++++++++++- deployment/core/config/base_config.py | 150 ++++++---- .../core/evaluation/verification_mixin.py | 6 +- deployment/projects/centerpoint/evaluator.py | 15 +- .../centerpoint/pipelines/artifacts.py | 64 ----- .../projects/centerpoint/pipelines/onnx.py | 8 +- .../centerpoint/pipelines/tensorrt.py | 8 +- deployment/runtime/evaluation_orchestrator.py | 7 +- 9 files changed, 381 insertions(+), 145 deletions(-) delete mode 100644 deployment/projects/centerpoint/pipelines/artifacts.py diff --git a/deployment/core/__init__.py b/deployment/core/__init__.py index 3c073b541..e635f3e89 100644 --- a/deployment/core/__init__.py +++ b/deployment/core/__init__.py @@ -1,6 +1,12 @@ """Core components for deployment framework.""" -from deployment.core.artifacts import Artifact +from deployment.core.artifacts import ( + Artifact, + get_component_files, + resolve_artifact_path, + resolve_engine_path, + resolve_onnx_path, +) from deployment.core.backend import Backend from deployment.core.config.base_config import ( BaseDeploymentConfig, @@ -76,6 +82,10 @@ "VerificationMixin", # Artifacts "Artifact", + "resolve_artifact_path", + "resolve_onnx_path", + "resolve_engine_path", + "get_component_files", "ModelSpec", # Preprocessing "build_preprocessing_pipeline", diff --git a/deployment/core/artifacts.py b/deployment/core/artifacts.py index 985aa3bb1..085fa2c96 100644 --- a/deployment/core/artifacts.py +++ b/deployment/core/artifacts.py @@ -1,18 +1,266 @@ -"""Artifact descriptors for deployment outputs.""" +""" +Artifact Path Resolution for Deployment Pipelines. + +This module provides: +1. Artifact dataclass - represents an exported model artifact +2. Path resolution functions - resolve artifact paths from deploy config + +Supports: +- Single-component models (YOLOX, Calibration): use component="model" +- Multi-component models (CenterPoint): use component="voxel_encoder", "backbone_head", etc. +""" from __future__ import annotations +import logging +import os import os.path as osp from dataclasses import dataclass +from typing import Any, Dict, Mapping, Optional + +logger = logging.getLogger(__name__) + + +# ============================================================================ +# Artifact Dataclass +# ============================================================================ @dataclass(frozen=True) class Artifact: - """Represents a produced deployment artifact such as ONNX or TensorRT outputs.""" + """ + Represents an exported model artifact (ONNX file, TensorRT engine, etc.). + + Attributes: + path: Filesystem path to the artifact (file or directory). + multi_file: True if artifact is a directory containing multiple files + (e.g., CenterPoint has voxel_encoder.onnx + backbone_head.onnx). + """ path: str multi_file: bool = False def exists(self) -> bool: - """Return True if the artifact path currently exists on disk.""" - return osp.exists(self.path) + """Check if the artifact exists on disk.""" + return os.path.exists(self.path) + + def is_directory(self) -> bool: + """Check if the artifact is a directory.""" + return os.path.isdir(self.path) + + def __str__(self) -> str: + return self.path + + +# ============================================================================ +# Path Resolution Functions +# ============================================================================ + +# File extension mapping +FILE_EXTENSIONS: Dict[str, str] = { + "onnx_file": ".onnx", + "engine_file": ".engine", +} + + +def resolve_artifact_path( + *, + base_dir: str, + components_cfg: Optional[Mapping[str, Any]], + component: str, + file_key: str, +) -> str: + """Resolve artifact path for any component. + + This is the entry point for artifact path resolution. + + Args: + base_dir: Base directory for artifacts (onnx_dir or tensorrt_dir), + or direct path to an artifact file. + components_cfg: The `components` dict from deploy_config. + Can be None for backwards compatibility. + component: Component name (e.g., 'model', 'voxel_encoder', 'backbone_head') + file_key: Key to look up ('onnx_file' or 'engine_file') + default_filename: Fallback filename if not specified in config + + Returns: + Resolved path to the artifact file + + Resolution strategy (single supported mode): + 1. `base_dir` must be a directory (e.g., `.../onnx` or `.../tensorrt`) + 2. Require `components_cfg[component][file_key]` to be set + - must be a relative path resolved under `base_dir` + 3. The resolved path must exist and be a file + + This function intentionally does NOT: + - scan directories for matching extensions + - fall back to default filenames + - accept `base_dir` as a file path + - accept absolute paths in `components` (enforces fully config-driven, workspace-relative artifacts) + + Examples: + # Single-component model (YOLOX) + resolve_artifact_path( + base_dir="work_dirs/yolox/onnx", + components_cfg={"model": {"onnx_file": "yolox.onnx"}}, + component="model", + file_key="onnx_file", + ) + + # Multi-component model (CenterPoint) + resolve_artifact_path( + base_dir="work_dirs/centerpoint/tensorrt", + components_cfg={"voxel_encoder": {"engine_file": "voxel.engine"}}, + component="voxel_encoder", + file_key="engine_file", + ) + """ + if not os.path.isdir(base_dir): + raise ValueError( + "Artifact resolution requires `base_dir` to be a directory. " + f"Got: {base_dir}. " + "Set evaluation.backends..{model_dir|engine_dir} to the artifact directory, " + "and set the artifact filename in deploy config under components.*.{onnx_file|engine_file}." + ) + + # Require filename from components config + filename = _get_filename_from_config(components_cfg, component, file_key) + if not filename: + raise KeyError( + "Missing artifact filename in deploy config. " + f"Expected components['{component}']['{file_key}'] to be set." + ) + + if osp.isabs(filename): + raise ValueError( + "Absolute artifact paths are not allowed. " + f"Set components['{component}']['{file_key}'] to a relative filename under base_dir instead. " + f"(got: {filename})" + ) + + base_abs = osp.abspath(base_dir) + path = osp.abspath(osp.join(base_abs, filename)) + # Prevent escaping base_dir via '../' + if osp.commonpath([base_abs, path]) != base_abs: + raise ValueError( + "Artifact path must stay within base_dir. " + f"Got components['{component}']['{file_key}']={filename} which resolves to {path} outside {base_abs}." + ) + if not os.path.isfile(path): + raise FileNotFoundError( + f"Configured artifact file not found: {path}. " + f"(base_dir={base_dir}, component={component}, file_key={file_key})" + ) + return path + + +def _get_filename_from_config( + components_cfg: Optional[Mapping[str, Any]], + component: str, + file_key: str, +) -> Optional[str]: + """Extract filename from components config.""" + if not components_cfg: + return None + + comp_cfg = components_cfg.get(component, {}) + if not isinstance(comp_cfg, Mapping): + return None + + filename = comp_cfg.get(file_key) + if isinstance(filename, str) and filename: + return filename + return None + + +def _search_directory_for_artifact( + directory: str, + file_key: str, + default_filename: str, +) -> Optional[str]: + """Search directory for matching artifact file.""" + ext = FILE_EXTENSIONS.get(file_key, "") + if not ext: + return None + + try: + matching_files = [f for f in os.listdir(directory) if f.endswith(ext)] + except OSError: + return None + + if not matching_files: + return None + + # Single file: use it + if len(matching_files) == 1: + resolved = osp.join(directory, matching_files[0]) + logger.info(f"Resolved artifact path: {directory} -> {resolved}") + return resolved + + # Multiple files: prefer default_filename + if default_filename in matching_files: + resolved = osp.join(directory, default_filename) + logger.info(f"Resolved artifact path using default: {resolved}") + return resolved + + # Otherwise use the first one (with warning) + resolved = osp.join(directory, matching_files[0]) + logger.warning(f"Multiple {ext} files found in {directory}, using first one: {matching_files[0]}") + return resolved + + +def get_component_files( + components_cfg: Mapping[str, Any], + file_key: str, +) -> Dict[str, str]: + """Get all component filenames for a given file type. + + Useful for multi-component models to enumerate all artifacts. + + Args: + components_cfg: The unified `components` dict from deploy_config + file_key: Key to look up ('onnx_file' or 'engine_file') + + Returns: + Dict mapping component name to filename + + Example: + >>> components = {"voxel_encoder": {"onnx_file": "voxel.onnx"}, + ... "backbone_head": {"onnx_file": "head.onnx"}} + >>> get_component_files(components, "onnx_file") + {"voxel_encoder": "voxel.onnx", "backbone_head": "head.onnx"} + """ + result = {} + for comp_name, comp_cfg in components_cfg.items(): + if isinstance(comp_cfg, Mapping) and file_key in comp_cfg: + result[comp_name] = comp_cfg[file_key] + return result + + +# Convenience aliases for common use cases +def resolve_onnx_path( + base_dir: str, + components_cfg: Optional[Mapping[str, Any]] = None, + component: str = "model", +) -> str: + """Convenience function for resolving ONNX paths.""" + return resolve_artifact_path( + base_dir=base_dir, + components_cfg=components_cfg, + component=component, + file_key="onnx_file", + ) + + +def resolve_engine_path( + base_dir: str, + components_cfg: Optional[Mapping[str, Any]] = None, + component: str = "model", +) -> str: + """Convenience function for resolving TensorRT engine paths.""" + return resolve_artifact_path( + base_dir=base_dir, + components_cfg=components_cfg, + component=component, + file_key="engine_file", + ) diff --git a/deployment/core/config/base_config.py b/deployment/core/config/base_config.py index be155f21d..174202c90 100644 --- a/deployment/core/config/base_config.py +++ b/deployment/core/config/base_config.py @@ -12,7 +12,7 @@ from dataclasses import dataclass, field from enum import Enum from types import MappingProxyType -from typing import Any, Dict, Iterable, Mapping, Optional, Tuple, Union +from typing import Any, Dict, Mapping, Optional, Tuple, Union import torch from mmengine.config import Config @@ -177,41 +177,36 @@ class TensorRTConfig: """ Configuration for TensorRT backend-specific settings. + Uses config structure: + tensorrt_config = dict(precision_policy="auto", max_workspace_size=1<<30) + + TensorRT profiles are defined in components.*.tensorrt_profile. + Note: The deploy config key for this section is **`tensorrt_config`**. """ - common_config: Mapping[str, Any] = field(default_factory=_empty_mapping) - model_inputs: Tuple[TensorRTModelInputConfig, ...] = field(default_factory=tuple) - components: Mapping[str, Mapping[str, Any]] = field(default_factory=_empty_mapping) + precision_policy: str = PrecisionPolicy.AUTO.value + max_workspace_size: int = DEFAULT_WORKSPACE_SIZE @classmethod def from_dict(cls, config_dict: Mapping[str, Any]) -> "TensorRTConfig": - common_config = dict(config_dict.get("common_config", {})) - model_inputs_raw: Iterable[Mapping[str, Any]] = config_dict.get("model_inputs", []) or [] - model_inputs: Tuple[TensorRTModelInputConfig, ...] = tuple( - TensorRTModelInputConfig.from_dict(item) for item in model_inputs_raw - ) - components_raw = dict(config_dict.get("components", {}) or {}) - components_frozen = {k: MappingProxyType(dict(v or {})) for k, v in components_raw.items()} return cls( - common_config=MappingProxyType(common_config), - model_inputs=model_inputs, - components=MappingProxyType(components_frozen), + precision_policy=config_dict.get("precision_policy", PrecisionPolicy.AUTO.value), + max_workspace_size=config_dict.get("max_workspace_size", DEFAULT_WORKSPACE_SIZE), ) def get_precision_policy(self) -> str: """Get precision policy name.""" - return self.common_config.get("precision_policy", PrecisionPolicy.AUTO.value) + return self.precision_policy def get_precision_flags(self) -> Mapping[str, bool]: """Get TensorRT precision flags for the configured policy.""" - policy = self.get_precision_policy() - return PRECISION_POLICIES.get(policy, {}) + return PRECISION_POLICIES.get(self.precision_policy, {}) def get_max_workspace_size(self) -> int: """Get maximum workspace size for TensorRT.""" - return self.common_config.get("max_workspace_size", DEFAULT_WORKSPACE_SIZE) + return self.max_workspace_size @dataclass(frozen=True) @@ -345,9 +340,8 @@ def _validate_config(self) -> None: raise ValueError(str(exc)) from exc # Validate precision policy if present - tensorrt_config = self.deploy_cfg.get("tensorrt_config", {}) - common_cfg = tensorrt_config.get("common_config", {}) - precision_policy = common_cfg.get("precision_policy", PrecisionPolicy.AUTO.value) + tensorrt_config = self.deploy_cfg.get("tensorrt_config", {}) or {} + precision_policy = tensorrt_config.get("precision_policy", PrecisionPolicy.AUTO.value) if precision_policy not in PRECISION_POLICIES: raise ValueError( f"Invalid precision_policy '{precision_policy}'. " f"Must be one of {list(PRECISION_POLICIES.keys())}" @@ -462,72 +456,126 @@ def task_type(self) -> Optional[str]: def get_onnx_settings(self) -> ONNXExportConfig: """ - Get ONNX export settings. + Get ONNX export settings from unified components configuration. + + Reads I/O from components.model.io.{inputs, outputs, dynamic_axes} Returns: ONNXExportConfig instance containing ONNX export parameters """ onnx_config = self.onnx_config - model_io = self.deploy_cfg.get("model_io", {}) - - # Get batch size and dynamic axes from model_io - batch_size = model_io.get("batch_size", None) - dynamic_axes = model_io.get("dynamic_axes", None) - - # If batch_size is set to a number, disable dynamic_axes - if batch_size is not None and isinstance(batch_size, int): - dynamic_axes = None - - # Handle multiple inputs and outputs - input_names = [model_io.get("input_name", "input")] - output_names = [model_io.get("output_name", "output")] + components_io = self._get_model_io_from_components() - # Add additional inputs if specified - additional_inputs = model_io.get("additional_inputs", []) - for additional_input in additional_inputs: - if isinstance(additional_input, dict): - input_names.append(additional_input.get("name", "input")) + # Get input/output names from components + input_names = [inp.get("name", "input") for inp in components_io.get("inputs", [])] + output_names = [out.get("name", "output") for out in components_io.get("outputs", [])] - # Add additional outputs if specified - additional_outputs = model_io.get("additional_outputs", []) - for additional_output in additional_outputs: - if isinstance(additional_output, str): - output_names.append(additional_output) + # Fallback to defaults if components not configured + if not input_names: + input_names = ["input"] + if not output_names: + output_names = ["output"] settings_dict = { "opset_version": onnx_config.get("opset_version", 16), "do_constant_folding": onnx_config.get("do_constant_folding", True), "input_names": tuple(input_names), "output_names": tuple(output_names), - "dynamic_axes": dynamic_axes, + "dynamic_axes": components_io.get("dynamic_axes"), "export_params": onnx_config.get("export_params", True), "keep_initializers_as_inputs": onnx_config.get("keep_initializers_as_inputs", False), "verbose": onnx_config.get("verbose", False), - "save_file": onnx_config.get("save_file", "model.onnx"), - "batch_size": batch_size, + "save_file": components_io.get("onnx_file") or onnx_config.get("save_file", "model.onnx"), + "batch_size": None, } - # Note: simplify is typically True by default, but can be overridden if "simplify" in onnx_config: settings_dict["simplify"] = onnx_config["simplify"] return ONNXExportConfig.from_mapping(settings_dict) + def _get_model_io_from_components(self) -> Dict[str, Any]: + """ + Extract model I/O configuration from components. + + For end-to-end models (single component), returns the io config + from components.model. + + Returns: + Dictionary with inputs, outputs, dynamic_axes, and onnx_file. + """ + components = self.deploy_cfg.get("components", {}) + if not components: + return {} + + # For single-component models, look for 'model' component + if "model" in components: + comp_cfg = components["model"] + io_cfg = comp_cfg.get("io", {}) + return { + "inputs": io_cfg.get("inputs", []), + "outputs": io_cfg.get("outputs", []), + "dynamic_axes": io_cfg.get("dynamic_axes"), + "onnx_file": comp_cfg.get("onnx_file"), + } + + return {} + def get_tensorrt_settings(self) -> TensorRTExportConfig: """ - Get TensorRT export settings with precision policy support. + Get TensorRT export settings from unified components configuration. + + TensorRT profiles are read from components.model.tensorrt_profile. Returns: TensorRTExportConfig instance containing TensorRT export parameters """ + model_inputs = self._build_model_inputs_from_components() + settings_dict = { "max_workspace_size": self.tensorrt_config.get_max_workspace_size(), "precision_policy": self.tensorrt_config.get_precision_policy(), "policy_flags": self.tensorrt_config.get_precision_flags(), - "model_inputs": self.tensorrt_config.model_inputs, + "model_inputs": model_inputs, } return TensorRTExportConfig.from_mapping(settings_dict) + def _build_model_inputs_from_components(self) -> Tuple[TensorRTModelInputConfig, ...]: + """ + Build model_inputs from components configuration. + + For end-to-end models (single component), extracts tensorrt_profile + from components.model and converts to TensorRTModelInputConfig format. + + Returns: + Tuple of TensorRTModelInputConfig, or empty tuple if not configured. + """ + components = self.deploy_cfg.get("components", {}) + if not components or "model" not in components: + return () + + comp_cfg = components["model"] + tensorrt_profile = comp_cfg.get("tensorrt_profile", {}) + + if not tensorrt_profile: + return () + + from deployment.exporters.common.configs import TensorRTProfileConfig + + input_shapes = {} + for input_name, shape_cfg in tensorrt_profile.items(): + if isinstance(shape_cfg, Mapping): + input_shapes[input_name] = TensorRTProfileConfig( + min_shape=tuple(shape_cfg.get("min_shape", [])), + opt_shape=tuple(shape_cfg.get("opt_shape", [])), + max_shape=tuple(shape_cfg.get("max_shape", [])), + ) + + if input_shapes: + return (TensorRTModelInputConfig(input_shapes=MappingProxyType(input_shapes)),) + + return () + def setup_logging(level: str = "INFO") -> logging.Logger: """ diff --git a/deployment/core/evaluation/verification_mixin.py b/deployment/core/evaluation/verification_mixin.py index 9b44c2110..0fb8c60b4 100644 --- a/deployment/core/evaluation/verification_mixin.py +++ b/deployment/core/evaluation/verification_mixin.py @@ -417,17 +417,17 @@ def _verify_single_sample( logger: logging.Logger, ) -> bool: """Verify a single sample.""" - input_data, metadata = self._get_verification_input(sample_idx, data_loader, ref_device) + input_data, infer_kwargs = self._get_verification_input(sample_idx, data_loader, ref_device) ref_name = f"{ref_backend.value} ({ref_device})" logger.info(f"\nRunning {ref_name} reference...") - ref_result = ref_pipeline.infer(input_data, metadata, return_raw_outputs=True) + ref_result = ref_pipeline.infer(input_data, return_raw_outputs=True, **infer_kwargs) logger.info(f" {ref_name} latency: {ref_result.latency_ms:.2f} ms") test_input = self._move_input_to_device(input_data, test_device) test_name = f"{test_backend.value} ({test_device})" logger.info(f"\nRunning {test_name} test...") - test_result = test_pipeline.infer(test_input, metadata, return_raw_outputs=True) + test_result = test_pipeline.infer(test_input, return_raw_outputs=True, **infer_kwargs) logger.info(f" {test_name} latency: {test_result.latency_ms:.2f} ms") passed, _ = self._compare_backend_outputs(ref_result.output, test_result.output, tolerance, test_name, logger) diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index a44fb8462..e745818ed 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -126,24 +126,25 @@ def _build_results( num_samples: int, ) -> EvalResultDict: latency_stats = self.compute_latency_stats(latencies) - latency_payload = latency_stats.to_dict() - - if latency_breakdowns: - latency_payload["latency_breakdown"] = self._compute_latency_breakdown(latency_breakdowns).to_dict() map_results = self.metrics_interface.compute_metrics() summary = self.metrics_interface.get_summary() summary_dict = summary.to_dict() if hasattr(summary, "to_dict") else summary - return { + result: EvalResultDict = { "mAP": summary_dict.get("mAP", 0.0), "mAPH": summary_dict.get("mAPH", 0.0), "per_class_ap": summary_dict.get("per_class_ap", {}), "detailed_metrics": map_results, - "latency": latency_payload, + "latency": latency_stats, # Store LatencyStats directly "num_samples": num_samples, } + if latency_breakdowns: + result["latency_breakdown"] = self._compute_latency_breakdown(latency_breakdowns) + + return result + def print_results(self, results: EvalResultDict) -> None: print("\n" + "=" * 80) print(f"{self.task_profile.display_name} - Evaluation Results") @@ -165,7 +166,7 @@ def print_results(self, results: EvalResultDict) -> None: print(f" {class_name:<12}: {ap:.4f}") if "latency" in results: - latency = results["latency"] + latency = results["latency"].to_dict() print("\nLatency Statistics:") print(f" Mean: {latency['mean_ms']:.2f} ms") print(f" Std: {latency['std_ms']:.2f} ms") diff --git a/deployment/projects/centerpoint/pipelines/artifacts.py b/deployment/projects/centerpoint/pipelines/artifacts.py deleted file mode 100644 index 34d5ea0e7..000000000 --- a/deployment/projects/centerpoint/pipelines/artifacts.py +++ /dev/null @@ -1,64 +0,0 @@ -""" -Artifact path helpers for CenterPoint pipelines. - -Resolves component artifact paths from the unified deploy config. -""" - -from __future__ import annotations - -import os.path as osp -from typing import Any, Mapping - - -def resolve_component_artifact_path( - *, - base_dir: str, - components_cfg: Mapping[str, Any], - component: str, - file_key: str, - default_filename: str, -) -> str: - """Resolve an artifact path for one component. - - Args: - base_dir: Base directory for artifacts (onnx_dir or tensorrt_dir) - components_cfg: The unified `components` dict from deploy_config - component: Component name (e.g., 'voxel_encoder', 'backbone_head') - file_key: Key to look up ('onnx_file' or 'engine_file') - default_filename: Fallback filename if not specified in config - - Returns: - Absolute path to the artifact file - - Priority: - - `components_cfg[component][file_key]` if present - - otherwise `default_filename` - - Supports absolute paths in config; otherwise joins with `base_dir`. - """ - comp_cfg = components_cfg.get(component, {}) or {} - if not isinstance(comp_cfg, Mapping): - raise TypeError(f"components['{component}'] must be a mapping, got {type(comp_cfg)}") - - filename = comp_cfg.get(file_key, default_filename) - if not isinstance(filename, str) or not filename: - raise TypeError(f"components['{component}']['{file_key}'] must be a non-empty str, got {type(filename)}") - - return filename if osp.isabs(filename) else osp.join(base_dir, filename) - - -def get_component_files(components_cfg: Mapping[str, Any], file_key: str) -> dict[str, str]: - """Get all component filenames for a given file type. - - Args: - components_cfg: The unified `components` dict from deploy_config - file_key: Key to look up ('onnx_file' or 'engine_file') - - Returns: - Dict mapping component name to filename - """ - result = {} - for comp_name, comp_cfg in components_cfg.items(): - if isinstance(comp_cfg, Mapping) and file_key in comp_cfg: - result[comp_name] = comp_cfg[file_key] - return result diff --git a/deployment/projects/centerpoint/pipelines/onnx.py b/deployment/projects/centerpoint/pipelines/onnx.py index f43177512..d933cd402 100644 --- a/deployment/projects/centerpoint/pipelines/onnx.py +++ b/deployment/projects/centerpoint/pipelines/onnx.py @@ -12,7 +12,7 @@ import onnxruntime as ort import torch -from deployment.projects.centerpoint.pipelines.artifacts import resolve_component_artifact_path +from deployment.core.artifacts import resolve_artifact_path from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline logger = logging.getLogger(__name__) @@ -63,19 +63,17 @@ def _load_onnx_models(self, device: str) -> None: FileNotFoundError: If ONNX model files are not found. RuntimeError: If model loading fails. """ - voxel_encoder_path = resolve_component_artifact_path( + voxel_encoder_path = resolve_artifact_path( base_dir=self.onnx_dir, components_cfg=self._components_cfg, component="voxel_encoder", file_key="onnx_file", - default_filename="pts_voxel_encoder.onnx", ) - backbone_head_path = resolve_component_artifact_path( + backbone_head_path = resolve_artifact_path( base_dir=self.onnx_dir, components_cfg=self._components_cfg, component="backbone_head", file_key="onnx_file", - default_filename="pts_backbone_neck_head.onnx", ) if not osp.exists(voxel_encoder_path): diff --git a/deployment/projects/centerpoint/pipelines/tensorrt.py b/deployment/projects/centerpoint/pipelines/tensorrt.py index 5d8acaefe..8c18d86e2 100644 --- a/deployment/projects/centerpoint/pipelines/tensorrt.py +++ b/deployment/projects/centerpoint/pipelines/tensorrt.py @@ -14,12 +14,12 @@ import tensorrt as trt import torch +from deployment.core.artifacts import resolve_artifact_path from deployment.pipelines.gpu_resource_mixin import ( GPUResourceMixin, TensorRTResourceManager, release_tensorrt_resources, ) -from deployment.projects.centerpoint.pipelines.artifacts import resolve_component_artifact_path from deployment.projects.centerpoint.pipelines.centerpoint_pipeline import CenterPointDeploymentPipeline logger = logging.getLogger(__name__) @@ -80,19 +80,17 @@ def _load_tensorrt_engines(self) -> None: runtime = trt.Runtime(self._logger) engine_files = { - "voxel_encoder": resolve_component_artifact_path( + "voxel_encoder": resolve_artifact_path( base_dir=self.tensorrt_dir, components_cfg=self._components_cfg, component="voxel_encoder", file_key="engine_file", - default_filename="pts_voxel_encoder.engine", ), - "backbone_head": resolve_component_artifact_path( + "backbone_head": resolve_artifact_path( base_dir=self.tensorrt_dir, components_cfg=self._components_cfg, component="backbone_head", file_key="engine_file", - default_filename="pts_backbone_neck_head.engine", ), } diff --git a/deployment/runtime/evaluation_orchestrator.py b/deployment/runtime/evaluation_orchestrator.py index 44fe299ef..783b800bf 100644 --- a/deployment/runtime/evaluation_orchestrator.py +++ b/deployment/runtime/evaluation_orchestrator.py @@ -201,11 +201,8 @@ def _print_cross_backend_comparison(self, all_results: Mapping[str, Any]) -> Non if "mAP" in results: self.logger.info(f" mAP: {results.get('mAP', 0):.4f}") - if "latency_stats" in results: - stats = results["latency_stats"] - self.logger.info(f" Latency: {stats['mean_ms']:.2f} ± {stats['std_ms']:.2f} ms") - elif "latency" in results: + if "latency" in results: latency = results["latency"] - self.logger.info(f" Latency: {latency['mean_ms']:.2f} ± {latency['std_ms']:.2f} ms") + self.logger.info(f" Latency: {latency.mean_ms:.2f} ± {latency.std_ms:.2f} ms") else: self.logger.info(" No results available") From 6dfdc597f2f394ba98ae8db9c531a40700f3de13 Mon Sep 17 00:00:00 2001 From: vividf Date: Fri, 9 Jan 2026 13:28:27 +0900 Subject: [PATCH 12/16] chore: fix kwargs Signed-off-by: vividf --- deployment/core/__init__.py | 2 ++ deployment/core/evaluation/base_evaluator.py | 18 ++++++++---- deployment/core/evaluation/evaluator_types.py | 18 +++++++++++- .../core/evaluation/verification_mixin.py | 28 ++++++++++++++----- deployment/projects/centerpoint/evaluator.py | 7 +++-- .../projects/centerpoint/pipelines/pytorch.py | 22 +-------------- 6 files changed, 58 insertions(+), 37 deletions(-) diff --git a/deployment/core/__init__.py b/deployment/core/__init__.py index e635f3e89..1afb0be1a 100644 --- a/deployment/core/__init__.py +++ b/deployment/core/__init__.py @@ -32,6 +32,7 @@ BaseEvaluator, EvalResultDict, EvaluationDefaults, + InferenceInput, ModelSpec, TaskProfile, VerifyResultDict, @@ -77,6 +78,7 @@ # Evaluation "BaseEvaluator", "TaskProfile", + "InferenceInput", "EvalResultDict", "VerifyResultDict", "VerificationMixin", diff --git a/deployment/core/evaluation/base_evaluator.py b/deployment/core/evaluation/base_evaluator.py index 23d251ae9..94c7b420b 100644 --- a/deployment/core/evaluation/base_evaluator.py +++ b/deployment/core/evaluation/base_evaluator.py @@ -23,6 +23,7 @@ from deployment.core.backend import Backend from deployment.core.evaluation.evaluator_types import ( EvalResultDict, + InferenceInput, InferenceResult, LatencyBreakdown, LatencyStats, @@ -38,6 +39,7 @@ "EvalResultDict", "VerifyResultDict", "ModelSpec", + "InferenceInput", "InferenceResult", "LatencyStats", "LatencyBreakdown", @@ -160,8 +162,14 @@ def _prepare_input( sample: Mapping[str, Any], data_loader: BaseDataLoader, device: str, - ) -> Tuple[Any, Dict[str, Any]]: - """Prepare model input from a sample. Returns (input_data, inference_kwargs).""" + ) -> InferenceInput: + """Prepare model input from a sample. + + Returns: + InferenceInput containing: + - data: The actual input data (e.g., points tensor) + - metadata: Sample metadata forwarded to postprocess() + """ raise NotImplementedError @abstractmethod @@ -211,7 +219,7 @@ def _get_verification_input( sample_idx: int, data_loader: BaseDataLoader, device: str, - ) -> Tuple[Any, Dict[str, Any]]: + ) -> InferenceInput: """Get verification input.""" sample = data_loader.load_sample(sample_idx) return self._prepare_input(sample, data_loader, device) @@ -254,12 +262,12 @@ def evaluate( logger.info(f"Processing sample {idx + 1}/{actual_samples}") sample = data_loader.load_sample(idx) - input_data, infer_kwargs = self._prepare_input(sample, data_loader, model.device) + inference_input = self._prepare_input(sample, data_loader, model.device) gt_data = data_loader.get_ground_truth(idx) ground_truths = self._parse_ground_truths(gt_data) - infer_result = pipeline.infer(input_data, **infer_kwargs) + infer_result = pipeline.infer(inference_input.data, metadata=inference_input.metadata) latencies.append(infer_result.latency_ms) if infer_result.breakdown: latency_breakdowns.append(infer_result.breakdown) diff --git a/deployment/core/evaluation/evaluator_types.py b/deployment/core/evaluation/evaluator_types.py index de800656f..b44cd3822 100644 --- a/deployment/core/evaluation/evaluator_types.py +++ b/deployment/core/evaluation/evaluator_types.py @@ -7,7 +7,7 @@ from __future__ import annotations -from dataclasses import asdict, dataclass +from dataclasses import asdict, dataclass, field from typing import Any, Dict, Optional, TypedDict from deployment.core.artifacts import Artifact @@ -93,6 +93,22 @@ def to_dict(self) -> Dict[str, Dict[str, float]]: return {stage: stats.to_dict() for stage, stats in self.stages.items()} +@dataclass +class InferenceInput: + """Prepared input for pipeline inference. + + This replaces the old (input_data, infer_kwargs) tuple pattern, + making the interface explicit and statically checkable. + + Attributes: + data: The actual input data (e.g., points tensor, image tensor). + metadata: Sample metadata forwarded to postprocess(). + """ + + data: Any + metadata: Dict[str, Any] = field(default_factory=dict) + + @dataclass(frozen=True) class InferenceResult: """Standard inference return payload.""" diff --git a/deployment/core/evaluation/verification_mixin.py b/deployment/core/evaluation/verification_mixin.py index 0fb8c60b4..45ef8dccd 100644 --- a/deployment/core/evaluation/verification_mixin.py +++ b/deployment/core/evaluation/verification_mixin.py @@ -16,7 +16,7 @@ import torch from deployment.core.backend import Backend -from deployment.core.evaluation.evaluator_types import ModelSpec, VerifyResultDict +from deployment.core.evaluation.evaluator_types import InferenceInput, ModelSpec, VerifyResultDict from deployment.core.io.base_data_loader import BaseDataLoader @@ -71,8 +71,14 @@ def _get_verification_input( sample_idx: int, data_loader: BaseDataLoader, device: str, - ) -> Tuple[Any, Dict[str, Any]]: - """Get input data for verification.""" + ) -> InferenceInput: + """Get input data for verification. + + Returns: + InferenceInput containing: + - data: The actual input data (e.g., points tensor) + - metadata: Sample metadata forwarded to postprocess() + """ raise NotImplementedError def _get_output_names(self) -> Optional[List[str]]: @@ -417,17 +423,25 @@ def _verify_single_sample( logger: logging.Logger, ) -> bool: """Verify a single sample.""" - input_data, infer_kwargs = self._get_verification_input(sample_idx, data_loader, ref_device) + inference_input = self._get_verification_input(sample_idx, data_loader, ref_device) ref_name = f"{ref_backend.value} ({ref_device})" logger.info(f"\nRunning {ref_name} reference...") - ref_result = ref_pipeline.infer(input_data, return_raw_outputs=True, **infer_kwargs) + ref_result = ref_pipeline.infer( + inference_input.data, + metadata=inference_input.metadata, + return_raw_outputs=True, + ) logger.info(f" {ref_name} latency: {ref_result.latency_ms:.2f} ms") - test_input = self._move_input_to_device(input_data, test_device) + test_input = self._move_input_to_device(inference_input.data, test_device) test_name = f"{test_backend.value} ({test_device})" logger.info(f"\nRunning {test_name} test...") - test_result = test_pipeline.infer(test_input, return_raw_outputs=True, **infer_kwargs) + test_result = test_pipeline.infer( + test_input, + metadata=inference_input.metadata, + return_raw_outputs=True, + ) logger.info(f" {test_name} latency: {test_result.latency_ms:.2f} ms") passed, _ = self._compare_backend_outputs(ref_result.output, test_result.output, tolerance, test_name, logger) diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index e745818ed..3a4e6d8e3 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -3,7 +3,7 @@ """ import logging -from typing import Any, Dict, List, Mapping, Optional, Tuple +from typing import Any, Dict, List, Mapping, Optional from mmengine.config import Config @@ -12,6 +12,7 @@ Detection3DMetricsConfig, Detection3DMetricsInterface, EvalResultDict, + InferenceInput, ModelSpec, TaskProfile, ) @@ -91,7 +92,7 @@ def _prepare_input( sample: Dict[str, Any], data_loader: BaseDataLoader, device: str, - ) -> Tuple[Any, Dict[str, Any]]: + ) -> InferenceInput: if "points" in sample: points = sample["points"] else: @@ -99,7 +100,7 @@ def _prepare_input( points = input_data.get("points", input_data) metadata = sample.get("metainfo", {}) - return points, metadata + return InferenceInput(data=points, metadata=metadata) def _parse_predictions(self, pipeline_output: Any) -> List[Dict]: return pipeline_output if isinstance(pipeline_output, list) else [] diff --git a/deployment/projects/centerpoint/pipelines/pytorch.py b/deployment/projects/centerpoint/pipelines/pytorch.py index a3ddff528..35c9ab79d 100644 --- a/deployment/projects/centerpoint/pipelines/pytorch.py +++ b/deployment/projects/centerpoint/pipelines/pytorch.py @@ -5,7 +5,7 @@ from __future__ import annotations import logging -from typing import Any, Dict, List, Optional +from typing import List import torch @@ -31,26 +31,6 @@ def __init__(self, pytorch_model: torch.nn.Module, device: str = "cuda") -> None super().__init__(pytorch_model, device, backend_type="pytorch") logger.info("PyTorch pipeline initialized (ONNX-compatible staged inference)") - def infer( - self, - points: torch.Tensor, - sample_meta: Optional[Dict[str, Any]] = None, - return_raw_outputs: bool = False, - ) -> Any: - """Run inference on point cloud. - - Args: - points: Point cloud tensor [N, point_features]. - sample_meta: Optional sample metadata. - return_raw_outputs: Whether to return raw outputs. - - Returns: - Detection results or raw outputs. - """ - if sample_meta is None: - sample_meta = {} - return super().infer(points, sample_meta, return_raw_outputs=return_raw_outputs) - def run_voxel_encoder(self, input_features: torch.Tensor) -> torch.Tensor: """Run voxel encoder using PyTorch model. From 359bcbb42d0c1a289543ba944359079ba0345515 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 14 Jan 2026 17:51:15 +0900 Subject: [PATCH 13/16] chore: update metrics output Signed-off-by: vividf --- deployment/cli/main.py | 13 +- deployment/core/evaluation/base_evaluator.py | 2 +- deployment/core/io/base_data_loader.py | 20 +- .../core/metrics/base_metrics_interface.py | 23 ++- .../core/metrics/detection_2d_metrics.py | 56 +++-- .../core/metrics/detection_3d_metrics.py | 189 +++++++++++++---- .../centerpoint/config/deploy_config.py | 5 +- .../projects/centerpoint/data_loader.py | 193 +++++++----------- deployment/projects/centerpoint/evaluator.py | 43 ++-- deployment/runtime/evaluation_orchestrator.py | 7 +- 10 files changed, 317 insertions(+), 234 deletions(-) diff --git a/deployment/cli/main.py b/deployment/cli/main.py index 3a1906148..2ee48c360 100644 --- a/deployment/cli/main.py +++ b/deployment/cli/main.py @@ -11,6 +11,7 @@ import importlib import pkgutil import sys +import traceback from typing import List import deployment.projects as projects_pkg @@ -51,11 +52,13 @@ def build_parser() -> argparse.ArgumentParser: subparsers = parser.add_subparsers(dest="project", required=True) # Discover projects and import them so they can contribute args. + failed_projects: List[str] = [] for project_name in _discover_project_packages(): try: _import_and_register_project(project_name) - except Exception: - # Skip broken/incomplete project bundles rather than breaking the whole CLI. + except Exception as e: + tb = traceback.format_exc() + failed_projects.append(f"- {project_name}: {e}\n{tb}") continue try: @@ -68,6 +71,12 @@ def build_parser() -> argparse.ArgumentParser: adapter.add_args(sub) sub.set_defaults(_adapter_name=project_name) + if not project_registry.list(): + details = "\n".join(failed_projects) if failed_projects else "(no project packages discovered)" + raise RuntimeError( + "No deployment projects were registered. This usually means project imports failed.\n" f"{details}" + ) + return parser diff --git a/deployment/core/evaluation/base_evaluator.py b/deployment/core/evaluation/base_evaluator.py index 94c7b420b..72ace770e 100644 --- a/deployment/core/evaluation/base_evaluator.py +++ b/deployment/core/evaluation/base_evaluator.py @@ -264,7 +264,7 @@ def evaluate( sample = data_loader.load_sample(idx) inference_input = self._prepare_input(sample, data_loader, model.device) - gt_data = data_loader.get_ground_truth(idx) + gt_data = sample.get("ground_truth", {}) ground_truths = self._parse_ground_truths(gt_data) infer_result = pipeline.infer(inference_input.data, metadata=inference_input.metadata) diff --git a/deployment/core/io/base_data_loader.py b/deployment/core/io/base_data_loader.py index bdc94c066..88d946f74 100644 --- a/deployment/core/io/base_data_loader.py +++ b/deployment/core/io/base_data_loader.py @@ -68,7 +68,7 @@ def load_sample(self, index: int) -> SampleData: raise NotImplementedError @abstractmethod - def preprocess(self, sample: SampleData) -> torch.Tensor: + def preprocess(self, sample: SampleData) -> Any: """ Preprocess raw sample data into model input format. @@ -76,8 +76,8 @@ def preprocess(self, sample: SampleData) -> torch.Tensor: sample: Raw sample data returned by load_sample() Returns: - Preprocessed tensor ready for model inference. - Shape and format depend on the specific task. + Preprocessed model input ready for inference. Type/shape is task-specific. + (e.g., torch.Tensor, Dict[str, torch.Tensor], tuple, etc.) Raises: ValueError: If sample format is invalid @@ -94,20 +94,6 @@ def get_num_samples(self) -> int: """ raise NotImplementedError - @abstractmethod - def get_ground_truth(self, index: int) -> Mapping[str, Any]: - """ - Get ground truth annotations for a specific sample. - - Args: - index: Sample index whose annotations should be returned - - Returns: - Dictionary containing task-specific ground truth data. - Implementations should raise IndexError if the index is invalid. - """ - raise NotImplementedError - def get_shape_sample(self, index: int = 0) -> Any: """ Return a representative sample used for export shape configuration. diff --git a/deployment/core/metrics/base_metrics_interface.py b/deployment/core/metrics/base_metrics_interface.py index 37feb8be4..c4a7d2c54 100644 --- a/deployment/core/metrics/base_metrics_interface.py +++ b/deployment/core/metrics/base_metrics_interface.py @@ -59,24 +59,27 @@ def to_dict(self) -> Dict[str, Any]: @dataclass(frozen=True) class DetectionSummary: - """Structured summary for detection metrics (2D/3D).""" + """Structured summary for detection metrics (2D/3D). - mAP: float = 0.0 - per_class_ap: Dict[str, float] = field(default_factory=dict) + All matching modes computed by autoware_perception_evaluation are included. + The `mAP_by_mode` and `mAPH_by_mode` dicts contain results for each matching mode. + """ + + mAP_by_mode: Dict[str, float] = field(default_factory=dict) + mAPH_by_mode: Dict[str, float] = field(default_factory=dict) + per_class_ap_by_mode: Dict[str, Dict[str, float]] = field(default_factory=dict) num_frames: int = 0 detailed_metrics: Dict[str, float] = field(default_factory=dict) - mAPH: Optional[float] = None def to_dict(self) -> Dict[str, Any]: - data = { - "mAP": self.mAP, - "per_class_ap": dict(self.per_class_ap), + """Convert to dict.""" + return { + "mAP_by_mode": dict(self.mAP_by_mode), + "mAPH_by_mode": dict(self.mAPH_by_mode), + "per_class_ap_by_mode": {k: dict(v) for k, v in self.per_class_ap_by_mode.items()}, "num_frames": self.num_frames, "detailed_metrics": dict(self.detailed_metrics), } - if self.mAPH is not None: - data["mAPH"] = self.mAPH - return data class BaseMetricsInterface(ABC): diff --git a/deployment/core/metrics/detection_2d_metrics.py b/deployment/core/metrics/detection_2d_metrics.py index fb9e73e5c..575dbb34f 100644 --- a/deployment/core/metrics/detection_2d_metrics.py +++ b/deployment/core/metrics/detection_2d_metrics.py @@ -452,27 +452,49 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float return metric_dict def get_summary(self) -> DetectionSummary: - """Get a summary of the evaluation including mAP and per-class metrics.""" + """Get a summary of the evaluation including mAP and per-class metrics for all matching modes.""" metrics = self.compute_metrics() - # Extract primary metrics (first mAP value found) - primary_map = None - per_class_ap = {} - - for key, value in metrics.items(): - if key.startswith("mAP_") and primary_map is None: - primary_map = value - elif "_AP_" in key and not key.startswith("mAP"): - # Extract class name from key - parts = key.split("_AP_") - if len(parts) == 2: - class_name = parts[0] - if class_name not in per_class_ap: - per_class_ap[class_name] = value + # Extract matching modes from metrics + modes = [] + for k in metrics.keys(): + if k.startswith("mAP_") and k != "mAP": + modes.append(k[len("mAP_") :]) + modes = list(dict.fromkeys(modes)) # Remove duplicates while preserving order + + if not modes: + return DetectionSummary( + mAP_by_mode={}, + mAPH_by_mode={}, + per_class_ap_by_mode={}, + num_frames=self._frame_count, + detailed_metrics=metrics, + ) + + # Collect mAP and per-class AP for each matching mode + mAP_by_mode: Dict[str, float] = {} + per_class_ap_by_mode: Dict[str, Dict[str, float]] = {} + + for mode in modes: + map_value = metrics.get(f"mAP_{mode}", 0.0) + mAP_by_mode[mode] = float(map_value) + + # Collect AP values per class for this mode + per_class_ap_values: Dict[str, List[float]] = {} + ap_key_infix = f"_AP_{mode}_" + for key, value in metrics.items(): + if ap_key_infix not in key or key.startswith("mAP"): + continue + class_name = key.split("_AP_", 1)[0] + per_class_ap_values.setdefault(class_name, []).append(float(value)) + + if per_class_ap_values: + per_class_ap_by_mode[mode] = {k: float(np.mean(v)) for k, v in per_class_ap_values.items() if v} return DetectionSummary( - mAP=primary_map or 0.0, - per_class_ap=per_class_ap, + mAP_by_mode=mAP_by_mode, + mAPH_by_mode={}, # 2D detection doesn't have mAPH + per_class_ap_by_mode=per_class_ap_by_mode, num_frames=self._frame_count, detailed_metrics=metrics, ) diff --git a/deployment/core/metrics/detection_3d_metrics.py b/deployment/core/metrics/detection_3d_metrics.py index 235ab795b..42907c791 100644 --- a/deployment/core/metrics/detection_3d_metrics.py +++ b/deployment/core/metrics/detection_3d_metrics.py @@ -25,9 +25,10 @@ """ import logging +import re import time -from dataclasses import dataclass, field -from typing import Any, Dict, List, Optional +from dataclasses import dataclass +from typing import Any, Dict, List, Mapping, Optional import numpy as np from perception_eval.common.dataset import FrameGroundTruth @@ -136,24 +137,6 @@ class Detection3DMetricsInterface(BaseMetricsInterface): This interface provides a simplified interface for the deployment framework to compute mAP, mAPH, and other detection metrics that are consistent with the T4MetricV2 used during training. - - Example usage: - config = Detection3DMetricsConfig( - class_names=["car", "truck", "bus", "bicycle", "pedestrian"], - frame_id="base_link", - ) - interface = Detection3DMetricsInterface(config) - - # Add frames - for pred, gt in zip(predictions_list, ground_truths_list): - interface.add_frame( - predictions=pred, # List[Dict] with bbox_3d, label, score - ground_truths=gt, # List[Dict] with bbox_3d, label - ) - - # Compute metrics - metrics = interface.compute_metrics() - # Returns: {"mAP_center_distance_bev_0.5": 0.7, ...} """ _UNKNOWN = "unknown" @@ -200,6 +183,15 @@ def __init__( # Initialize evaluation manager (will be created on first use or reset) self.evaluator: Optional[PerceptionEvaluationManager] = None + self.gt_count_total: int = 0 + self.pred_count_total: int = 0 + self.gt_count_by_label: Dict[str, int] = {} + self.pred_count_by_label: Dict[str, int] = {} + self._metric_score: Optional[MetricsScore] = None + + cfg_dict = config.evaluation_config_dict or {} + self._evaluation_cfg_dict: Dict[str, Any] = dict(cfg_dict) + def reset(self) -> None: """Reset the interface for a new evaluation session.""" self.evaluator = PerceptionEvaluationManager( @@ -208,6 +200,11 @@ def reset(self) -> None: metric_output_dir=None, ) self._frame_count = 0 + self.gt_count_total = 0 + self.pred_count_total = 0 + self.gt_count_by_label = {} + self.pred_count_by_label = {} + self._metric_score = None def _convert_index_to_label(self, label_index: int) -> Label: """Convert a label index to a Label object. @@ -381,6 +378,27 @@ def add_frame( if frame_name is None: frame_name = str(self._frame_count) + self.pred_count_total += len(predictions) + self.gt_count_total += len(ground_truths) + + for p in predictions: + try: + label = int(p.get("label", -1)) + except Exception: + label = -1 + if 0 <= label < len(self.class_names): + name = self.class_names[label] + self.pred_count_by_label[name] = self.pred_count_by_label.get(name, 0) + 1 + + for g in ground_truths: + try: + label = int(g.get("label", -1)) + except Exception: + label = -1 + if 0 <= label < len(self.class_names): + name = self.class_names[label] + self.gt_count_by_label[name] = self.gt_count_by_label.get(name, 0) + 1 + # Convert predictions to DynamicObject estimated_objects = self._predictions_to_dynamic_objects(predictions, unix_time) @@ -418,6 +436,7 @@ def compute_metrics(self) -> Dict[str, float]: try: # Get scene result (aggregated metrics) metrics_score: MetricsScore = self.evaluator.get_scene_result() + self._metric_score = metrics_score # Process metrics into a flat dictionary return self._process_metrics_score(metrics_score) @@ -429,6 +448,29 @@ def compute_metrics(self) -> Dict[str, float]: traceback.print_exc() return {} + @property + def metric_score(self) -> MetricsScore: + """Return the raw MetricsScore returned by autoware_perception_evaluation. + + Raises: + RuntimeError: If metrics haven't been computed yet. + """ + if self._metric_score is None: + raise RuntimeError("metric_score is not available yet. Call add_frame(...), then compute_metrics() first.") + return self._metric_score + + # Backward-compatible alias (can be removed once callers migrate). + @property + def last_metrics_score(self) -> MetricsScore: + """Alias of `metric_score`.""" + return self.metric_score + + def format_last_report(self) -> str: + """Format the last metrics report using perception_eval's own __str__ implementation.""" + if self._metric_score is None: + return "" + return str(self._metric_score) + def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float]: """Process MetricsScore into a flat dictionary. @@ -455,6 +497,21 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float key = f"{label_name}_AP_{matching_mode}_{threshold}" metric_dict[key] = ap_value + # Process individual APH values + label_to_aphs = getattr(map_instance, "label_to_aphs", None) + if label_to_aphs: + for label, aphs in label_to_aphs.items(): + label_name = label.value + for aph in aphs: + threshold = aph.matching_threshold + aph_value = getattr(aph, "aph", None) + if aph_value is None: + aph_value = getattr(aph, "ap", None) + if aph_value is None: + continue + key = f"{label_name}_APH_{matching_mode}_{threshold}" + metric_dict[key] = aph_value + # Add mAP and mAPH values map_key = f"mAP_{matching_mode}" maph_key = f"mAPH_{matching_mode}" @@ -463,32 +520,82 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float return metric_dict + @staticmethod + def _extract_matching_modes(metrics: Mapping[str, float]) -> List[str]: + """Extract matching modes from metrics dict keys (e.g., 'mAP_center_distance_bev' -> 'center_distance_bev').""" + modes = [] + for k in metrics.keys(): + if k.startswith("mAP_") and k != "mAP": + modes.append(k[len("mAP_") :]) + # Remove duplicates while preserving order + return list(dict.fromkeys(modes)) + + def get_thresholds_for_mode( + self, mode: str, metrics: Optional[Mapping[str, float]] = None + ) -> Optional[List[float]]: + """Return thresholds for a matching mode from config or inferred from metric keys.""" + cfg = self._evaluation_cfg_dict + threshold_key = f"{mode}_thresholds" + thresholds = cfg.get(threshold_key) + if thresholds is not None: + return [float(x) for x in thresholds] + + if not metrics: + return None + + pattern = re.compile(rf"_AP(H)?_{re.escape(mode)}_([-+]?\d*\.?\d+(?:[eE][-+]?\d+)?)$") + found: List[float] = [] + for k in metrics.keys(): + m = pattern.search(k) + if m: + try: + found.append(float(m.group(2))) + except Exception: + pass + return sorted(set(found)) if found else None + def get_summary(self) -> DetectionSummary: - """Get a summary of the evaluation including mAP and per-class metrics.""" + """Get a summary of the evaluation including mAP and per-class metrics for all matching modes.""" metrics = self.compute_metrics() - # Extract primary metrics (first mAP value found) - primary_map = None - primary_maph = None - per_class_ap = {} - - for key, value in metrics.items(): - if key.startswith("mAP_") and primary_map is None: - primary_map = value - elif key.startswith("mAPH_") and primary_maph is None: - primary_maph = value - elif "_AP_" in key and not key.startswith("mAP"): - # Extract class name from key - parts = key.split("_AP_") - if len(parts) == 2: - class_name = parts[0] - if class_name not in per_class_ap: - per_class_ap[class_name] = value + modes = self._extract_matching_modes(metrics) + if not modes: + return DetectionSummary( + mAP_by_mode={}, + mAPH_by_mode={}, + per_class_ap_by_mode={}, + num_frames=self._frame_count, + detailed_metrics=metrics, + ) + + # Collect mAP/mAPH and per-class AP for each matching mode + mAP_by_mode: Dict[str, float] = {} + mAPH_by_mode: Dict[str, float] = {} + per_class_ap_by_mode: Dict[str, Dict[str, float]] = {} + + for mode in modes: + map_value = metrics.get(f"mAP_{mode}", 0.0) + maph_value = metrics.get(f"mAPH_{mode}", 0.0) + mAP_by_mode[mode] = float(map_value) + if maph_value != 0.0 or f"mAPH_{mode}" in metrics: + mAPH_by_mode[mode] = float(maph_value) + + # Collect AP values per class for this mode + per_class_ap_values: Dict[str, List[float]] = {} + ap_key_infix = f"_AP_{mode}_" + for key, value in metrics.items(): + if ap_key_infix not in key: + continue + class_name = key.split("_AP_", 1)[0] + per_class_ap_values.setdefault(class_name, []).append(float(value)) + + if per_class_ap_values: + per_class_ap_by_mode[mode] = {k: float(np.mean(v)) for k, v in per_class_ap_values.items() if v} return DetectionSummary( - mAP=primary_map or 0.0, - mAPH=primary_maph or 0.0, - per_class_ap=per_class_ap, + mAP_by_mode=mAP_by_mode, + mAPH_by_mode=mAPH_by_mode, + per_class_ap_by_mode=per_class_ap_by_mode, num_frames=self._frame_count, detailed_metrics=metrics, ) diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py index f64136516..b1ae404e3 100644 --- a/deployment/projects/centerpoint/config/deploy_config.py +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -25,7 +25,7 @@ # Export Configuration # ============================================================================ export = dict( - mode="both", + mode="none", work_dir="work_dirs/centerpoint_deployment", onnx_path=None, ) @@ -110,7 +110,8 @@ # Runtime I/O settings # ============================================================================ runtime_io = dict( - info_file="data/t4dataset/info/t4dataset_j6gen2_infos_val.pkl", + # This should be a path relative to `data_root` in the model config. + info_file="info/t4dataset_j6gen2_infos_val.pkl", sample_idx=1, ) diff --git a/deployment/projects/centerpoint/data_loader.py b/deployment/projects/centerpoint/data_loader.py index eb94c14e9..bd8c4f3a4 100644 --- a/deployment/projects/centerpoint/data_loader.py +++ b/deployment/projects/centerpoint/data_loader.py @@ -1,25 +1,34 @@ """ CenterPoint DataLoader for deployment. + +Wraps MMDet3D Dataset to ensure GT is identical to tools/detection3d/test.py. +Pipeline is run once per sample in load_sample(), avoiding redundant computation. """ -import os -import pickle +import copy from typing import Any, Dict, List, Optional, Union +import mmdet3d.datasets.transforms # noqa: F401 - registers transforms import numpy as np import torch from mmengine.config import Config +from mmengine.registry import DATASETS, init_default_scope +from mmengine.utils import import_modules_from_strings -from deployment.core import BaseDataLoader, build_preprocessing_pipeline +from deployment.core import BaseDataLoader class CenterPointDataLoader(BaseDataLoader): - """Deployment dataloader for CenterPoint. + """Deployment dataloader for CenterPoint using MMDet3D Dataset. + + This wraps the same Dataset used by tools/detection3d/test.py, ensuring: + - GT is identical + - Pipeline processing is identical + - Pipeline runs once per sample (no cache needed) - Responsibilities: - - Load `info_file` (pickle) entries describing samples. - - Build and run the MMEngine preprocessing pipeline for each sample. - - Provide `load_sample()` for export helpers that need raw sample metadata. + Design: + load_sample() runs the full pipeline and returns all data (input + GT). + preprocess() extracts model inputs from the loaded sample. """ def __init__( @@ -36,15 +45,26 @@ def __init__( } ) - if not os.path.exists(info_file): - raise FileNotFoundError(f"Info file not found: {info_file}") - - self.info_file = info_file self.model_cfg = model_cfg self.device = device + self.info_file = info_file + self.dataset = self._build_dataset(model_cfg, info_file) + + def _build_dataset(self, model_cfg: Config, info_file: str) -> Any: + """Build MMDet3D Dataset from config, overriding ann_file.""" + # Set default scope to mmdet3d so transforms are found in the registry + init_default_scope("mmdet3d") + if not hasattr(model_cfg, "test_dataloader"): + raise ValueError("model_cfg must have 'test_dataloader' with dataset config") + + dataset_cfg = copy.deepcopy(model_cfg.test_dataloader.dataset) + + dataset_cfg["ann_file"] = info_file + dataset_cfg["test_mode"] = True - self.data_infos = self._load_info_file() - self.pipeline = build_preprocessing_pipeline(model_cfg, task_type=task_type) + # Build dataset + dataset = DATASETS.build(dataset_cfg) + return dataset def _to_tensor( self, @@ -75,124 +95,65 @@ def _to_tensor( f"Unexpected type for '{name}': {type(data)}. Expected torch.Tensor, np.ndarray, or list of tensors/arrays." ) - def _load_info_file(self) -> list: - try: - with open(self.info_file, "rb") as f: - data = pickle.load(f) - except Exception as e: - raise ValueError(f"Failed to load info file: {e}") from e - - if isinstance(data, dict): - if "data_list" in data: - data_list = data["data_list"] - elif "infos" in data: - data_list = data["infos"] - else: - raise ValueError(f"Expected 'data_list' or 'infos' in info file, found keys: {list(data.keys())}") - elif isinstance(data, list): - data_list = data - else: - raise ValueError(f"Unexpected info file format: {type(data)}") - - if not data_list: - raise ValueError("No samples found in info file") - - return data_list - def load_sample(self, index: int) -> Dict[str, Any]: - if index >= len(self.data_infos): - raise IndexError(f"Sample index {index} out of range (0-{len(self.data_infos)-1})") - - info = self.data_infos[index] - - lidar_points = info.get("lidar_points", {}) - if not lidar_points: - lidar_path = info.get("lidar_path", info.get("velodyne_path", "")) - lidar_points = {"lidar_path": lidar_path} - - if "lidar_path" in lidar_points and not lidar_points["lidar_path"].startswith("/"): - data_root = getattr(self.model_cfg, "data_root", "data/t4dataset/") - if not data_root.endswith("/"): - data_root += "/" - if not lidar_points["lidar_path"].startswith(data_root): - lidar_points["lidar_path"] = data_root + lidar_points["lidar_path"] - - instances = info.get("instances", []) - - sample = { - "lidar_points": lidar_points, - "sample_idx": info.get("sample_idx", index), - "timestamp": info.get("timestamp", 0), - } - - if instances: - gt_bboxes_3d = [] - gt_labels_3d = [] + """Load sample by running the full pipeline once. - for instance in instances: - if "bbox_3d" in instance and "bbox_label_3d" in instance: - if instance.get("bbox_3d_isvalid", True): - gt_bboxes_3d.append(instance["bbox_3d"]) - gt_labels_3d.append(instance["bbox_label_3d"]) + Returns a dict containing all data needed for inference and evaluation: + - points: Points tensor (ready for inference) + - metainfo: Sample metadata + - ground_truth: Raw eval_ann_info from MMDet3D (kept unconverted) + """ + if index >= len(self.dataset): + raise IndexError(f"Sample index {index} out of range (0-{len(self.dataset)-1})") - if gt_bboxes_3d: - sample["gt_bboxes_3d"] = np.array(gt_bboxes_3d, dtype=np.float32) - sample["gt_labels_3d"] = np.array(gt_labels_3d, dtype=np.int64) + # Run pipeline once + data = self.dataset[index] - if "images" in info or "img_path" in info: - sample["images"] = info.get("images", {}) - if "img_path" in info: - sample["img_path"] = info["img_path"] - - return sample - - def preprocess(self, sample: Dict[str, Any]) -> Union[Dict[str, torch.Tensor], torch.Tensor]: - results = self.pipeline(sample) - - if "inputs" not in results: - raise ValueError( - "Expected 'inputs' key in pipeline results (MMDet3D 3.x format). " - f"Found keys: {list(results.keys())}. " - "Please ensure your test pipeline includes Pack3DDetInputs transform." - ) - - pipeline_inputs = results["inputs"] + # Extract inputs + pipeline_inputs = data.get("inputs", {}) if "points" not in pipeline_inputs: - available_keys = list(pipeline_inputs.keys()) - raise ValueError( - "Expected 'points' key in pipeline inputs for CenterPoint. " - f"Available keys: {available_keys}. " - "For CenterPoint, voxelization is performed by the model's data_preprocessor." - ) + raise ValueError(f"Expected 'points' in inputs. Got keys: {list(pipeline_inputs.keys())}") points_tensor = self._to_tensor(pipeline_inputs["points"], name="points") if points_tensor.ndim != 2: - raise ValueError(f"Expected points tensor with shape [N, point_features], got shape {points_tensor.shape}") + raise ValueError(f"Expected points tensor with shape [N, features], got {points_tensor.shape}") - return {"points": points_tensor} + # Extract metainfo and eval_ann_info from data_samples + data_samples = data.get("data_samples") + metainfo: Dict[str, Any] = {} + ground_truth: Dict[str, Any] = {} - def get_num_samples(self) -> int: - return len(self.data_infos) - - def get_ground_truth(self, index: int) -> Dict[str, Any]: - sample = self.load_sample(index) + if data_samples is not None: + metainfo = getattr(data_samples, "metainfo", {}) or {} + eval_ann_info = getattr(data_samples, "eval_ann_info", {}) or {} + # Keep raw eval_ann_info here; evaluator will convert to the metrics format. + ground_truth = dict(eval_ann_info) - gt_bboxes_3d = sample.get("gt_bboxes_3d", np.zeros((0, 7), dtype=np.float32)) - gt_labels_3d = sample.get("gt_labels_3d", np.zeros((0,), dtype=np.int64)) + return { + "points": points_tensor, + "metainfo": metainfo, + "ground_truth": ground_truth, + } - if isinstance(gt_bboxes_3d, (list, tuple)): - gt_bboxes_3d = np.array(gt_bboxes_3d, dtype=np.float32) - if isinstance(gt_labels_3d, (list, tuple)): - gt_labels_3d = np.array(gt_labels_3d, dtype=np.int64) + def preprocess(self, sample: Dict[str, Any]) -> Dict[str, Any]: + """Extract points and metainfo from loaded sample. + This is a lightweight operation - pipeline already ran in load_sample(). + """ return { - "gt_bboxes_3d": gt_bboxes_3d, - "gt_labels_3d": gt_labels_3d, - "sample_idx": sample.get("sample_idx", index), + "points": sample["points"], + "metainfo": sample["metainfo"], } + def get_num_samples(self) -> int: + return len(self.dataset) + def get_class_names(self) -> List[str]: + # Get from dataset's metainfo or model_cfg + if hasattr(self.dataset, "metainfo") and "classes" in self.dataset.metainfo: + return list(self.dataset.metainfo["classes"]) + if hasattr(self.model_cfg, "class_names"): - return self.model_cfg.class_names + return list(self.model_cfg.class_names) - raise ValueError("class_names must be defined in model_cfg.") + raise ValueError("class_names not found in dataset.metainfo or model_cfg") diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index 3a4e6d8e3..b8f646814 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -5,6 +5,7 @@ import logging from typing import Any, Dict, List, Mapping, Optional +import numpy as np from mmengine.config import Config from deployment.core import ( @@ -95,11 +96,9 @@ def _prepare_input( ) -> InferenceInput: if "points" in sample: points = sample["points"] + metadata = sample.get("metainfo", {}) else: - input_data = data_loader.preprocess(sample) - points = input_data.get("points", input_data) - - metadata = sample.get("metainfo", {}) + raise ValueError(f"Expected 'points' in sample. Got keys: {list(sample.keys())}") return InferenceInput(data=points, metadata=metadata) def _parse_predictions(self, pipeline_output: Any) -> List[Dict]: @@ -112,6 +111,11 @@ def _parse_ground_truths(self, gt_data: Dict[str, Any]) -> List[Dict]: gt_bboxes_3d = gt_data["gt_bboxes_3d"] gt_labels_3d = gt_data["gt_labels_3d"] + gt_bboxes_3d = np.asarray(gt_bboxes_3d, dtype=np.float32).reshape( + -1, np.asarray(gt_bboxes_3d).shape[-1] if np.asarray(gt_bboxes_3d).ndim > 1 else 7 + ) + gt_labels_3d = np.asarray(gt_labels_3d, dtype=np.int64).reshape(-1) + for i in range(len(gt_bboxes_3d)): ground_truths.append({"bbox_3d": gt_bboxes_3d[i].tolist(), "label": int(gt_labels_3d[i])}) @@ -133,9 +137,9 @@ def _build_results( summary_dict = summary.to_dict() if hasattr(summary, "to_dict") else summary result: EvalResultDict = { - "mAP": summary_dict.get("mAP", 0.0), - "mAPH": summary_dict.get("mAPH", 0.0), - "per_class_ap": summary_dict.get("per_class_ap", {}), + "mAP_by_mode": summary_dict.get("mAP_by_mode", {}), + "mAPH_by_mode": summary_dict.get("mAPH_by_mode", {}), + "per_class_ap_by_mode": summary_dict.get("per_class_ap_by_mode", {}), "detailed_metrics": map_results, "latency": latency_stats, # Store LatencyStats directly "num_samples": num_samples, @@ -147,24 +151,12 @@ def _build_results( return result def print_results(self, results: EvalResultDict) -> None: - print("\n" + "=" * 80) - print(f"{self.task_profile.display_name} - Evaluation Results") - print("(Using autoware_perception_evaluation for consistent metrics)") - print("=" * 80) - - print("\nDetection Metrics:") - print(f" mAP: {results.get('mAP', 0.0):.4f}") - print(f" mAPH: {results.get('mAPH', 0.0):.4f}") - - if "per_class_ap" in results: - print("\nPer-Class AP:") - for class_id, ap in results["per_class_ap"].items(): - class_name = ( - class_id - if isinstance(class_id, str) - else (self.class_names[class_id] if class_id < len(self.class_names) else f"class_{class_id}") - ) - print(f" {class_name:<12}: {ap:.4f}") + interface = self.metrics_interface # type: ignore[assignment] + text = interface.format_last_report() + if text: + print(text) + print(f"\nTotal Samples: {results.get('num_samples', 0)}") + return if "latency" in results: latency = results["latency"].to_dict() @@ -187,4 +179,3 @@ def print_results(self, results: EvalResultDict) -> None: print(f" {stage_name:18s}: {stats['mean_ms']:.2f} ± {stats['std_ms']:.2f} ms") print(f"\nTotal Samples: {results.get('num_samples', 0)}") - print("=" * 80) diff --git a/deployment/runtime/evaluation_orchestrator.py b/deployment/runtime/evaluation_orchestrator.py index 783b800bf..befb729ea 100644 --- a/deployment/runtime/evaluation_orchestrator.py +++ b/deployment/runtime/evaluation_orchestrator.py @@ -198,8 +198,11 @@ def _print_cross_backend_comparison(self, all_results: Mapping[str, Any]) -> Non if results and "error" not in results: if "accuracy" in results: self.logger.info(f" Accuracy: {results.get('accuracy', 0):.4f}") - if "mAP" in results: - self.logger.info(f" mAP: {results.get('mAP', 0):.4f}") + if "mAP_by_mode" in results: + mAP_by_mode = results.get("mAP_by_mode", {}) + if mAP_by_mode: + for mode, map_value in mAP_by_mode.items(): + self.logger.info(f" mAP ({mode}): {map_value:.4f}") if "latency" in results: latency = results["latency"] From f7a90c1f7a9ce77b372fb0738e990221749831c7 Mon Sep 17 00:00:00 2001 From: vividf Date: Wed, 14 Jan 2026 20:03:26 +0900 Subject: [PATCH 14/16] chore: clean code Signed-off-by: vividf --- deployment/core/artifacts.py | 37 ------------------- deployment/projects/centerpoint/evaluator.py | 17 +++++++-- .../onnx_models/centerpoint_onnx.py | 17 ++++----- projects/CenterPoint/README.md | 15 +++++++- 4 files changed, 34 insertions(+), 52 deletions(-) diff --git a/deployment/core/artifacts.py b/deployment/core/artifacts.py index 085fa2c96..d9bbfc3f3 100644 --- a/deployment/core/artifacts.py +++ b/deployment/core/artifacts.py @@ -81,7 +81,6 @@ def resolve_artifact_path( Can be None for backwards compatibility. component: Component name (e.g., 'model', 'voxel_encoder', 'backbone_head') file_key: Key to look up ('onnx_file' or 'engine_file') - default_filename: Fallback filename if not specified in config Returns: Resolved path to the artifact file @@ -173,42 +172,6 @@ def _get_filename_from_config( return None -def _search_directory_for_artifact( - directory: str, - file_key: str, - default_filename: str, -) -> Optional[str]: - """Search directory for matching artifact file.""" - ext = FILE_EXTENSIONS.get(file_key, "") - if not ext: - return None - - try: - matching_files = [f for f in os.listdir(directory) if f.endswith(ext)] - except OSError: - return None - - if not matching_files: - return None - - # Single file: use it - if len(matching_files) == 1: - resolved = osp.join(directory, matching_files[0]) - logger.info(f"Resolved artifact path: {directory} -> {resolved}") - return resolved - - # Multiple files: prefer default_filename - if default_filename in matching_files: - resolved = osp.join(directory, default_filename) - logger.info(f"Resolved artifact path using default: {resolved}") - return resolved - - # Otherwise use the first one (with warning) - resolved = osp.join(directory, matching_files[0]) - logger.warning(f"Multiple {ext} files found in {directory}, using first one: {matching_files[0]}") - return resolved - - def get_component_files( components_cfg: Mapping[str, Any], file_key: str, diff --git a/deployment/projects/centerpoint/evaluator.py b/deployment/projects/centerpoint/evaluator.py index b8f646814..04f148136 100644 --- a/deployment/projects/centerpoint/evaluator.py +++ b/deployment/projects/centerpoint/evaluator.py @@ -73,11 +73,20 @@ def _get_output_names(self) -> List[str]: io_cfg = backbone_head_cfg.get("io", {}) outputs = io_cfg.get("outputs", []) - if outputs: - return [out.get("name") for out in outputs if out.get("name")] + if not outputs: + raise ValueError( + "Output names must be provided via components_cfg.backbone_head.io.outputs. " + "No fallback values are allowed in deployment framework." + ) + + output_names = [out.get("name") for out in outputs if out.get("name")] + if not output_names: + raise ValueError( + "Output names must be provided via components_cfg.backbone_head.io.outputs. " + "Each output must have a 'name' field." + ) - # Fallback to default output names - return ["heatmap", "reg", "height", "dim", "rot", "vel"] + return output_names def _create_pipeline(self, model_spec: ModelSpec, device: str) -> Any: return PipelineFactory.create( diff --git a/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py b/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py index ec83124d6..8332ac818 100644 --- a/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py +++ b/deployment/projects/centerpoint/onnx_models/centerpoint_onnx.py @@ -77,18 +77,15 @@ def _get_inputs(self, data_loader, sample_idx=0): sample = data_loader.load_sample(sample_idx) - if "lidar_points" not in sample: - raise KeyError("Sample does not contain 'lidar_points'") + if "points" not in sample: + raise KeyError(f"Sample must contain 'points' (processed tensor). Got keys: {list(sample.keys())}") - lidar_path = sample["lidar_points"].get("lidar_path") - if not lidar_path: - raise ValueError("Sample must provide 'lidar_path' inside 'lidar_points'") + points = sample["points"] + if not isinstance(points, torch.Tensor): + raise TypeError(f"Expected points to be torch.Tensor, got {type(points)}") - if not os.path.exists(lidar_path): - raise FileNotFoundError(f"Lidar path not found: {lidar_path}") - - points = self._load_point_cloud(lidar_path) - points = torch.from_numpy(points).to(self._torch_device) + # Ensure points are on the correct device + points = points.to(self._torch_device) points = [points] return {"points": points, "data_samples": None} diff --git a/projects/CenterPoint/README.md b/projects/CenterPoint/README.md index cff9fa8e9..839fbd498 100644 --- a/projects/CenterPoint/README.md +++ b/projects/CenterPoint/README.md @@ -42,6 +42,19 @@ docker run -it --rm --gpus all --shm-size=64g --name awml -p 6006:6006 -v $PWD/: ``` For ONNX and TensorRT evaluation + +- If you need to use deployment, ONNX runtime, or TensorRT evaluation, please build the docker image first: + +```sh +# Build the base autoware-ml image (if not already built) +DOCKER_BUILDKIT=1 docker build -t autoware-ml . + +# Build the centerpoint-deployment image +docker build -t centerpoint-deployment:latest -f projects/CenterPoint/Dockerfile . +``` + +- Run the docker container: + ```sh docker run -it --rm --gpus all --shm-size=64g --name awml_deployment -p 6006:6006 -v $PWD/:/workspace -v $PWD/data:/workspace/data centerpoint-deployment:latest ``` @@ -115,7 +128,7 @@ where `frame-range` represents the range of frames to visualize. ### 5. Deploy -- Run the unified deployment pipeline: +- Run the deployment pipeline: - Export ONNX/TensorRT artifacts. - Verify the exported artifacts. - (Optionally) run evaluation. From 97d977b3e1e7e049524e8fdf0476ebb1a411de67 Mon Sep 17 00:00:00 2001 From: vividf Date: Thu, 15 Jan 2026 20:09:51 +0900 Subject: [PATCH 15/16] chore: clean up kwargs Signed-off-by: vividf --- deployment/core/contexts.py | 12 ------------ deployment/core/evaluation/evaluator_types.py | 3 --- .../core/metrics/base_metrics_interface.py | 2 +- deployment/exporters/common/base_exporter.py | 3 +-- deployment/exporters/common/model_wrappers.py | 19 ++++++------------- deployment/pipelines/base_factory.py | 4 ++-- deployment/pipelines/base_pipeline.py | 7 +++---- deployment/pipelines/factory.py | 7 ++++--- deployment/pipelines/registry.py | 4 ++-- .../centerpoint/config/deploy_config.py | 2 +- .../pipelines/centerpoint_pipeline.py | 2 -- .../projects/centerpoint/pipelines/factory.py | 2 -- 12 files changed, 20 insertions(+), 47 deletions(-) diff --git a/deployment/core/contexts.py b/deployment/core/contexts.py index 486caa1e5..8df2f8a23 100644 --- a/deployment/core/contexts.py +++ b/deployment/core/contexts.py @@ -1,18 +1,6 @@ """ Typed context objects for deployment workflows. -This module defines typed dataclasses that replace **kwargs with explicit, -type-checked parameters. This improves: -- Type safety: Catches mismatches at type-check time -- Discoverability: IDE autocomplete shows available parameters -- Refactoring safety: Renamed fields are caught by type checkers - -Design Principles: - 1. Base contexts define common parameters across all projects - 2. Project-specific contexts extend base with additional fields - 3. Optional fields have sensible defaults - 4. Contexts are immutable (frozen=True) for safety - Usage: # Create context for export ctx = ExportContext(sample_idx=0) diff --git a/deployment/core/evaluation/evaluator_types.py b/deployment/core/evaluation/evaluator_types.py index b44cd3822..d6ae9fabc 100644 --- a/deployment/core/evaluation/evaluator_types.py +++ b/deployment/core/evaluation/evaluator_types.py @@ -97,9 +97,6 @@ def to_dict(self) -> Dict[str, Dict[str, float]]: class InferenceInput: """Prepared input for pipeline inference. - This replaces the old (input_data, infer_kwargs) tuple pattern, - making the interface explicit and statically checkable. - Attributes: data: The actual input data (e.g., points tensor, image tensor). metadata: Sample metadata forwarded to postprocess(). diff --git a/deployment/core/metrics/base_metrics_interface.py b/deployment/core/metrics/base_metrics_interface.py index c4a7d2c54..3d68245e3 100644 --- a/deployment/core/metrics/base_metrics_interface.py +++ b/deployment/core/metrics/base_metrics_interface.py @@ -128,7 +128,7 @@ def reset(self) -> None: pass @abstractmethod - def add_frame(self, *args, **kwargs) -> None: + def add_frame(self, *args) -> None: """ Add a frame of predictions and ground truths for evaluation. diff --git a/deployment/exporters/common/base_exporter.py b/deployment/exporters/common/base_exporter.py index 057ef9712..e2105694b 100644 --- a/deployment/exporters/common/base_exporter.py +++ b/deployment/exporters/common/base_exporter.py @@ -66,7 +66,7 @@ def prepare_model(self, model: torch.nn.Module) -> torch.nn.Module: return self._model_wrapper(model) @abstractmethod - def export(self, model: torch.nn.Module, sample_input: Any, output_path: str, **kwargs) -> None: + def export(self, model: torch.nn.Module, sample_input: Any, output_path: str) -> None: """ Export model to target format. @@ -74,7 +74,6 @@ def export(self, model: torch.nn.Module, sample_input: Any, output_path: str, ** model: PyTorch model to export sample_input: Example model input(s) for tracing/shape inference output_path: Path to save exported model - **kwargs: Additional format-specific arguments Raises: RuntimeError: If export fails diff --git a/deployment/exporters/common/model_wrappers.py b/deployment/exporters/common/model_wrappers.py index 24b798ba3..7f40efa07 100644 --- a/deployment/exporters/common/model_wrappers.py +++ b/deployment/exporters/common/model_wrappers.py @@ -10,7 +10,6 @@ """ from abc import ABC, abstractmethod -from typing import Any, Dict import torch import torch.nn as nn @@ -27,20 +26,18 @@ class BaseModelWrapper(nn.Module, ABC): base class if special output format conversion is needed. """ - def __init__(self, model: nn.Module, **kwargs): + def __init__(self, model: nn.Module): """ Initialize wrapper. Args: model: PyTorch model to wrap - **kwargs: Wrapper-specific arguments """ super().__init__() self.model = model - self._wrapper_config = kwargs @abstractmethod - def forward(self, *args, **kwargs): + def forward(self, *args): """ Forward pass for ONNX export. @@ -48,10 +45,6 @@ def forward(self, *args, **kwargs): """ raise NotImplementedError - def get_config(self) -> Dict[str, Any]: - """Get wrapper configuration.""" - return self._wrapper_config - class IdentityWrapper(BaseModelWrapper): """ @@ -61,9 +54,9 @@ class IdentityWrapper(BaseModelWrapper): This is the default wrapper for most models. """ - def __init__(self, model: nn.Module, **kwargs): - super().__init__(model, **kwargs) + def __init__(self, model: nn.Module): + super().__init__(model) - def forward(self, *args, **kwargs): + def forward(self, *args): """Forward pass without modification.""" - return self.model(*args, **kwargs) + return self.model(*args) diff --git a/deployment/pipelines/base_factory.py b/deployment/pipelines/base_factory.py index 4aa9f5c71..0576777c5 100644 --- a/deployment/pipelines/base_factory.py +++ b/deployment/pipelines/base_factory.py @@ -36,7 +36,7 @@ def create_pipeline( model_spec: ModelSpec, pytorch_model: Any, device: Optional[str] = None, - **kwargs, + components_cfg: Optional[Any] = None, ) -> BaseDeploymentPipeline: """Build and return a pipeline instance for the given model spec. @@ -49,7 +49,7 @@ def create_pipeline( model_spec: Describes the model path/device/backend and any metadata. pytorch_model: A loaded PyTorch model (used for PYTORCH backends). device: Optional device override (defaults to `model_spec.device`). - **kwargs: Project-specific options passed from evaluator/CLI. + components_cfg: Project-specific component configuration (e.g., file paths, IO specs). """ raise NotImplementedError diff --git a/deployment/pipelines/base_pipeline.py b/deployment/pipelines/base_pipeline.py index efa369523..122939096 100644 --- a/deployment/pipelines/base_pipeline.py +++ b/deployment/pipelines/base_pipeline.py @@ -44,7 +44,7 @@ def __init__(self, model: Any, device: str = "cpu", task_type: str = "unknown", logger.info(f"Initialized {self.__class__.__name__} on device: {self.device}") @abstractmethod - def preprocess(self, input_data: Any, **kwargs) -> Any: + def preprocess(self, input_data: Any) -> Any: """Convert raw input into model-ready tensors/arrays. Implementations may optionally return a tuple `(model_input, metadata_dict)` @@ -68,7 +68,7 @@ def postprocess(self, model_output: Any, metadata: Dict = None) -> Any: raise NotImplementedError def infer( - self, input_data: Any, metadata: Optional[Dict] = None, return_raw_outputs: bool = False, **kwargs + self, input_data: Any, metadata: Optional[Dict] = None, return_raw_outputs: bool = False ) -> InferenceResult: """Run end-to-end inference with latency breakdown. @@ -81,7 +81,6 @@ def infer( input_data: Raw input sample(s) in a project-defined format. metadata: Optional auxiliary context merged with preprocess metadata. return_raw_outputs: If True, skip `postprocess` and return raw model output. - **kwargs: Forwarded to `preprocess` for project-specific options. Returns: InferenceResult with `output`, total latency, and per-stage breakdown. @@ -94,7 +93,7 @@ def infer( try: start_time = time.perf_counter() - preprocessed = self.preprocess(input_data, **kwargs) + preprocessed = self.preprocess(input_data) preprocess_metadata = {} model_input = preprocessed diff --git a/deployment/pipelines/factory.py b/deployment/pipelines/factory.py index b7ef2290f..0dcce4cef 100644 --- a/deployment/pipelines/factory.py +++ b/deployment/pipelines/factory.py @@ -51,7 +51,7 @@ def create( model_spec: ModelSpec, pytorch_model: Any, device: Optional[str] = None, - **kwargs, + components_cfg: Optional[Any] = None, ) -> BaseDeploymentPipeline: """ Create a pipeline for the specified project. @@ -61,7 +61,7 @@ def create( model_spec: Model specification (backend/device/path) pytorch_model: PyTorch model instance device: Override device (uses model_spec.device if None) - **kwargs: Project-specific arguments + components_cfg: Project-specific component configuration Returns: Pipeline instance @@ -75,6 +75,7 @@ def create( ... "centerpoint", ... model_spec, ... pytorch_model, + ... components_cfg=components_cfg, ... ) """ return pipeline_registry.create_pipeline( @@ -82,7 +83,7 @@ def create( model_spec=model_spec, pytorch_model=pytorch_model, device=device, - **kwargs, + components_cfg=components_cfg, ) @staticmethod diff --git a/deployment/pipelines/registry.py b/deployment/pipelines/registry.py index 03e9f27b8..585da3c09 100644 --- a/deployment/pipelines/registry.py +++ b/deployment/pipelines/registry.py @@ -73,7 +73,7 @@ def create_pipeline( model_spec: ModelSpec, pytorch_model: Any, device: Optional[str] = None, - **kwargs, + components_cfg: Optional[Any] = None, ) -> BaseDeploymentPipeline: """Create a project-specific pipeline instance using the registered factory. @@ -85,7 +85,7 @@ def create_pipeline( model_spec=model_spec, pytorch_model=pytorch_model, device=device, - **kwargs, + components_cfg=components_cfg, ) def list_projects(self) -> list: diff --git a/deployment/projects/centerpoint/config/deploy_config.py b/deployment/projects/centerpoint/config/deploy_config.py index b1ae404e3..80dfa5b3f 100644 --- a/deployment/projects/centerpoint/config/deploy_config.py +++ b/deployment/projects/centerpoint/config/deploy_config.py @@ -25,7 +25,7 @@ # Export Configuration # ============================================================================ export = dict( - mode="none", + mode="both", work_dir="work_dirs/centerpoint_deployment", onnx_path=None, ) diff --git a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py index 4355ac3be..54259a936 100644 --- a/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py +++ b/deployment/projects/centerpoint/pipelines/centerpoint_pipeline.py @@ -106,7 +106,6 @@ def to_numpy(self, data: torch.Tensor, dtype: np.dtype = np.float32) -> np.ndarr def preprocess( self, points: torch.Tensor, - **kwargs: Any, ) -> Tuple[Dict[str, torch.Tensor], Dict[str, Any]]: """Preprocess point cloud data for inference. @@ -115,7 +114,6 @@ def preprocess( Args: points: Point cloud tensor of shape [N, point_features]. - **kwargs: Additional arguments (unused). Returns: Tuple of (preprocessed_dict, metadata_dict). diff --git a/deployment/projects/centerpoint/pipelines/factory.py b/deployment/projects/centerpoint/pipelines/factory.py index e6822bd50..8a513b790 100644 --- a/deployment/projects/centerpoint/pipelines/factory.py +++ b/deployment/projects/centerpoint/pipelines/factory.py @@ -39,7 +39,6 @@ def create_pipeline( pytorch_model: Any, device: Optional[str] = None, components_cfg: Optional[Mapping[str, Any]] = None, - **kwargs, ) -> BaseDeploymentPipeline: """Create a CenterPoint pipeline for the specified backend. @@ -49,7 +48,6 @@ def create_pipeline( device: Override device (uses model_spec.device if None) components_cfg: Unified component configuration dict from deploy_config. Used to configure component file paths. - **kwargs: Additional arguments (unused) Returns: Pipeline instance for the specified backend From a9ecfddfc0f1f99f1b62c9a52664d6e60562a160 Mon Sep 17 00:00:00 2001 From: vividf Date: Mon, 2 Feb 2026 18:53:24 +0900 Subject: [PATCH 16/16] chore: temp fix for t4metric2 Signed-off-by: vividf --- .../core/metrics/detection_3d_metrics.py | 280 ++++++++++++------ deployment/projects/centerpoint/evaluator.py | 58 ++-- .../centerpoint/pipelines/tensorrt.py | 93 +++++- deployment/runtime/evaluation_orchestrator.py | 6 + 4 files changed, 329 insertions(+), 108 deletions(-) diff --git a/deployment/core/metrics/detection_3d_metrics.py b/deployment/core/metrics/detection_3d_metrics.py index 42907c791..6bfc6ddd5 100644 --- a/deployment/core/metrics/detection_3d_metrics.py +++ b/deployment/core/metrics/detection_3d_metrics.py @@ -131,6 +131,7 @@ def __post_init__(self): class Detection3DMetricsInterface(BaseMetricsInterface): + # TODO(vividf): refactor this class after refactoring T4MetricV2 """ Interface for computing 3D detection metrics using autoware_perception_evaluation. @@ -159,52 +160,99 @@ def __init__( self.data_root = data_root self.result_root_directory = result_root_directory - # Create perception evaluation config - self.perception_eval_config = PerceptionEvaluationConfig( - dataset_paths=data_root, - frame_id=config.frame_id, - result_root_directory=result_root_directory, - evaluation_config_dict=config.evaluation_config_dict, - load_raw_data=False, - ) + cfg_dict = config.evaluation_config_dict or {} + self._evaluation_cfg_dict: Dict[str, Any] = dict(cfg_dict) - # Create critical object filter config - self.critical_object_filter_config = CriticalObjectFilterConfig( - evaluator_config=self.perception_eval_config, - **config.critical_object_filter_config, - ) + # Create multiple evaluators for different distance ranges (like T4MetricV2) + min_distance = cfg_dict.get("min_distance") + max_distance = cfg_dict.get("max_distance") + + if isinstance(min_distance, (int, float)) and isinstance(max_distance, (int, float)): + min_distance = [float(min_distance)] + max_distance = [float(max_distance)] + elif not isinstance(min_distance, list) or not isinstance(max_distance, list): + raise ValueError( + "min_distance and max_distance must be either scalars (int/float) or lists for multi-evaluator mode. " + f"Got min_distance={type(min_distance)}, max_distance={type(max_distance)}" + ) - # Create frame pass fail config - self.frame_pass_fail_config = PerceptionPassFailConfig( - evaluator_config=self.perception_eval_config, - **config.frame_pass_fail_config, - ) + if len(min_distance) != len(max_distance): + raise ValueError( + f"min_distance and max_distance must have the same length. " + f"Got len(min_distance)={len(min_distance)}, len(max_distance)={len(max_distance)}" + ) + + if len(min_distance) == 0: + raise ValueError("min_distance and max_distance lists cannot be empty") - # Initialize evaluation manager (will be created on first use or reset) - self.evaluator: Optional[PerceptionEvaluationManager] = None + # Create distance ranges and evaluators + self._bev_distance_ranges = list(zip(min_distance, max_distance)) + self.evaluators: Dict[str, Dict[str, Any]] = {} + self._create_evaluators(config) self.gt_count_total: int = 0 self.pred_count_total: int = 0 self.gt_count_by_label: Dict[str, int] = {} self.pred_count_by_label: Dict[str, int] = {} - self._metric_score: Optional[MetricsScore] = None + self._last_metrics_by_eval_name: Dict[str, MetricsScore] = {} + + def _create_evaluators(self, config: Detection3DMetricsConfig) -> None: + """Create multiple evaluators for different distance ranges (like T4MetricV2).""" + range_filter_name = "bev_center" + + for min_dist, max_dist in self._bev_distance_ranges: + # Create a copy of evaluation_config_dict with single distance values + eval_config_dict = dict(config.evaluation_config_dict or {}) + eval_config_dict["min_distance"] = min_dist + eval_config_dict["max_distance"] = max_dist + + # Create perception evaluation config for this range + evaluator_config = PerceptionEvaluationConfig( + dataset_paths=self.data_root, + frame_id=config.frame_id, + result_root_directory=self.result_root_directory, + evaluation_config_dict=eval_config_dict, + load_raw_data=False, + ) - cfg_dict = config.evaluation_config_dict or {} - self._evaluation_cfg_dict: Dict[str, Any] = dict(cfg_dict) + # Create critical object filter config + critical_object_filter_config = CriticalObjectFilterConfig( + evaluator_config=evaluator_config, + **config.critical_object_filter_config, + ) + + # Create frame pass fail config + frame_pass_fail_config = PerceptionPassFailConfig( + evaluator_config=evaluator_config, + **config.frame_pass_fail_config, + ) + + evaluator_name = f"{range_filter_name}_{min_dist}-{max_dist}" + + self.evaluators[evaluator_name] = { + "evaluator": None, # Will be created on reset + "evaluator_config": evaluator_config, + "critical_object_filter_config": critical_object_filter_config, + "frame_pass_fail_config": frame_pass_fail_config, + "bev_distance_range": (min_dist, max_dist), + } def reset(self) -> None: """Reset the interface for a new evaluation session.""" - self.evaluator = PerceptionEvaluationManager( - evaluation_config=self.perception_eval_config, - load_ground_truth=False, - metric_output_dir=None, - ) + # Reset all evaluators + for eval_name, eval_data in self.evaluators.items(): + eval_data["evaluator"] = PerceptionEvaluationManager( + evaluation_config=eval_data["evaluator_config"], + load_ground_truth=False, + metric_output_dir=None, + ) + self._frame_count = 0 self.gt_count_total = 0 self.pred_count_total = 0 self.gt_count_by_label = {} self.pred_count_by_label = {} - self._metric_score = None + self._last_metrics_by_eval_name = {} def _convert_index_to_label(self, label_index: int) -> Label: """Convert a label index to a Label object. @@ -371,7 +419,8 @@ def add_frame( - num_lidar_pts: int (optional) frame_name: Optional name for the frame. """ - if self.evaluator is None: + needs_reset = any(eval_data["evaluator"] is None for eval_data in self.evaluators.values()) + if needs_reset: self.reset() unix_time = time.time() @@ -405,15 +454,22 @@ def add_frame( # Convert ground truths to FrameGroundTruth frame_ground_truth = self._ground_truths_to_frame_ground_truth(ground_truths, unix_time, frame_name) - # Add frame result to evaluator + # Add frame result to all evaluators try: - self.evaluator.add_frame_result( - unix_time=unix_time, - ground_truth_now_frame=frame_ground_truth, - estimated_objects=estimated_objects, - critical_object_filter_config=self.critical_object_filter_config, - frame_pass_fail_config=self.frame_pass_fail_config, - ) + for eval_name, eval_data in self.evaluators.items(): + if eval_data["evaluator"] is None: + eval_data["evaluator"] = PerceptionEvaluationManager( + evaluation_config=eval_data["evaluator_config"], + load_ground_truth=False, + metric_output_dir=None, + ) + eval_data["evaluator"].add_frame_result( + unix_time=unix_time, + ground_truth_now_frame=frame_ground_truth, + estimated_objects=estimated_objects, + critical_object_filter_config=eval_data["critical_object_filter_config"], + frame_pass_fail_config=eval_data["frame_pass_fail_config"], + ) self._frame_count += 1 except Exception as e: logger.warning(f"Failed to add frame {frame_name}: {e}") @@ -423,23 +479,47 @@ def compute_metrics(self) -> Dict[str, float]: Returns: Dictionary of metrics with keys like: - - mAP_center_distance_bev_0.5 - - mAP_center_distance_bev_1.0 - - mAPH_center_distance_bev_0.5 - - car_AP_center_distance_bev_0.5 + - mAP_center_distance_bev (mean AP across all classes, no threshold) + - mAPH_center_distance_bev (mean APH across all classes, no threshold) + - car_AP_center_distance_bev_0.5 (per-class AP with threshold) + - car_AP_center_distance_bev_1.0 (per-class AP with threshold) + - car_APH_center_distance_bev_0.5 (per-class APH with threshold) + - etc. + For multi-evaluator mode, metrics are prefixed with evaluator name: + - bev_center_0.0-50.0_mAP_center_distance_bev + - bev_center_0.0-50.0_car_AP_center_distance_bev_0.5 + - bev_center_50.0-90.0_mAP_center_distance_bev - etc. + Note: mAP/mAPH keys do not include threshold; only per-class AP/APH keys do. """ - if self.evaluator is None or self._frame_count == 0: + if self._frame_count == 0: logger.warning("No frames to evaluate") return {} try: - # Get scene result (aggregated metrics) - metrics_score: MetricsScore = self.evaluator.get_scene_result() - self._metric_score = metrics_score + # Cache scene results to avoid recomputing + scene_results = {} + for eval_name, eval_data in self.evaluators.items(): + evaluator = eval_data["evaluator"] + if evaluator is None: + continue + + try: + metrics_score = evaluator.get_scene_result() + scene_results[eval_name] = metrics_score + except Exception as e: + logger.warning(f"Error computing metrics for {eval_name}: {e}") + + # Process cached metrics with evaluator name prefix + all_metrics = {} + for eval_name, metrics_score in scene_results.items(): + eval_metrics = self._process_metrics_score(metrics_score, prefix=eval_name) + all_metrics.update(eval_metrics) + + # Cache results for reuse by format_last_report() and get_summary() + self._last_metrics_by_eval_name = scene_results - # Process metrics into a flat dictionary - return self._process_metrics_score(metrics_score) + return all_metrics except Exception as e: logger.error(f"Error computing metrics: {e}") @@ -448,39 +528,42 @@ def compute_metrics(self) -> Dict[str, float]: traceback.print_exc() return {} - @property - def metric_score(self) -> MetricsScore: - """Return the raw MetricsScore returned by autoware_perception_evaluation. + def format_last_report(self) -> str: + """Format the last metrics report using perception_eval's own __str__ implementation. - Raises: - RuntimeError: If metrics haven't been computed yet. + For multi-evaluator mode, returns reports for all evaluators with distance range labels. + Uses cached results from compute_metrics() if available to avoid recomputation. """ - if self._metric_score is None: - raise RuntimeError("metric_score is not available yet. Call add_frame(...), then compute_metrics() first.") - return self._metric_score - - # Backward-compatible alias (can be removed once callers migrate). - @property - def last_metrics_score(self) -> MetricsScore: - """Alias of `metric_score`.""" - return self.metric_score + # Use cached results if available, otherwise compute them + if not self._last_metrics_by_eval_name: + # Cache not available, compute now + self.compute_metrics() + + # Format reports for all evaluators using cached results + reports = [] + for eval_name, metrics_score in self._last_metrics_by_eval_name.items(): + try: + # Extract distance range from evaluator name (e.g., "bev_center_0.0-50.0" -> "0.0-50.0") + distance_range = eval_name.replace("bev_center_", "") + report = f"\n{'='*80}\nDistance Range: {distance_range} m\n{'='*80}\n{str(metrics_score)}" + reports.append(report) + except Exception as e: + logger.warning(f"Error formatting report for {eval_name}: {e}") - def format_last_report(self) -> str: - """Format the last metrics report using perception_eval's own __str__ implementation.""" - if self._metric_score is None: - return "" - return str(self._metric_score) + return "\n".join(reports) if reports else "" - def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float]: + def _process_metrics_score(self, metrics_score: MetricsScore, prefix: Optional[str] = None) -> Dict[str, float]: """Process MetricsScore into a flat dictionary. Args: metrics_score: MetricsScore instance from evaluator. + prefix: Optional prefix to add to metric keys (for multi-evaluator mode). Returns: Flat dictionary of metrics. """ metric_dict = {} + key_prefix = f"{prefix}_" if prefix else "" for map_instance in metrics_score.mean_ap_values: matching_mode = map_instance.matching_mode.value.lower().replace(" ", "_") @@ -494,7 +577,7 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float ap_value = ap.ap # Create the metric key - key = f"{label_name}_AP_{matching_mode}_{threshold}" + key = f"{key_prefix}{label_name}_AP_{matching_mode}_{threshold}" metric_dict[key] = ap_value # Process individual APH values @@ -509,12 +592,12 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float aph_value = getattr(aph, "ap", None) if aph_value is None: continue - key = f"{label_name}_APH_{matching_mode}_{threshold}" + key = f"{key_prefix}{label_name}_APH_{matching_mode}_{threshold}" metric_dict[key] = aph_value # Add mAP and mAPH values - map_key = f"mAP_{matching_mode}" - maph_key = f"mAPH_{matching_mode}" + map_key = f"{key_prefix}mAP_{matching_mode}" + maph_key = f"{key_prefix}mAPH_{matching_mode}" metric_dict[map_key] = map_instance.map metric_dict[maph_key] = map_instance.maph @@ -522,11 +605,19 @@ def _process_metrics_score(self, metrics_score: MetricsScore) -> Dict[str, float @staticmethod def _extract_matching_modes(metrics: Mapping[str, float]) -> List[str]: - """Extract matching modes from metrics dict keys (e.g., 'mAP_center_distance_bev' -> 'center_distance_bev').""" - modes = [] + """Extract matching modes from metrics dict keys (e.g., 'mAP_center_distance_bev' -> 'center_distance_bev'). + + Supports both prefixed and non-prefixed formats: + - Non-prefixed: "mAP_center_distance_bev" + - Prefixed: "bev_center_0.0-50.0_mAP_center_distance_bev" + """ + # Matches either "mAP_" or "_mAP_" + pat = re.compile(r"(?:^|_)mAP_(.+)$") + modes: List[str] = [] for k in metrics.keys(): - if k.startswith("mAP_") and k != "mAP": - modes.append(k[len("mAP_") :]) + m = pat.search(k) + if m: + modes.append(m.group(1)) # Remove duplicates while preserving order return list(dict.fromkeys(modes)) @@ -569,24 +660,45 @@ def get_summary(self) -> DetectionSummary: ) # Collect mAP/mAPH and per-class AP for each matching mode + # Handle both prefixed (multi-evaluator) and non-prefixed metrics mAP_by_mode: Dict[str, float] = {} mAPH_by_mode: Dict[str, float] = {} per_class_ap_by_mode: Dict[str, Dict[str, float]] = {} for mode in modes: - map_value = metrics.get(f"mAP_{mode}", 0.0) - maph_value = metrics.get(f"mAPH_{mode}", 0.0) - mAP_by_mode[mode] = float(map_value) - if maph_value != 0.0 or f"mAPH_{mode}" in metrics: - mAPH_by_mode[mode] = float(maph_value) + map_values = [] + maph_values = [] + + # Use regex to match both prefixed and non-prefixed formats + map_pattern = re.compile(rf"(?:^|_)mAP_{re.escape(mode)}$") + maph_pattern = re.compile(rf"(?:^|_)mAPH_{re.escape(mode)}$") + + for key, value in metrics.items(): + if map_pattern.search(key): + map_values.append(float(value)) + if maph_pattern.search(key): + maph_values.append(float(value)) + + if map_values: + mAP_by_mode[mode] = float(np.mean(map_values)) + else: + mAP_by_mode[mode] = 0.0 + + if maph_values: + mAPH_by_mode[mode] = float(np.mean(maph_values)) # Collect AP values per class for this mode + # Parse class name from key format: "{prefix}_