From a72959c6f94da9ca63b2ded9827c98fb6d4f5383 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Dec 2023 16:19:47 +0900 Subject: [PATCH] refactor: update constructor of `PerceptionFrameResult` Signed-off-by: ktro2828 --- .../manager/perception_evaluation_manager.py | 18 ++++++++---- .../perception/perception_frame_result.py | 29 ++++++++++++------- 2 files changed, 30 insertions(+), 17 deletions(-) diff --git a/perception_eval/perception_eval/manager/perception_evaluation_manager.py b/perception_eval/perception_eval/manager/perception_evaluation_manager.py index 10652a2c..0c9dcd92 100644 --- a/perception_eval/perception_eval/manager/perception_evaluation_manager.py +++ b/perception_eval/perception_eval/manager/perception_evaluation_manager.py @@ -15,6 +15,7 @@ from __future__ import annotations from typing import List +from typing import Optional from typing import Tuple from typing import TYPE_CHECKING @@ -78,8 +79,8 @@ def add_frame_result( unix_time: int, ground_truth_now_frame: FrameGroundTruth, estimated_objects: List[ObjectType], - critical_ground_truth_objects: List[ObjectType], - frame_config: PerceptionFrameConfig, + critical_ground_truth_objects: Optional[List[ObjectType]] = None, + frame_config: Optional[PerceptionFrameConfig] = None, ) -> PerceptionFrameResult: """Get perception result at current frame. @@ -106,13 +107,18 @@ def add_frame_result( ground_truth_now_frame, ) + if critical_ground_truth_objects is None: + critical_ground_truth_objects = ground_truth_now_frame.objects.copy() + + if frame_config is None: + frame_config = PerceptionFrameConfig(self.config) + result = PerceptionFrameResult( + unix_time=unix_time, + frame_config=frame_config, + metrics_config=self.metrics_config, object_results=object_results, frame_ground_truth=ground_truth_now_frame, - metrics_config=self.metrics_config, - frame_config=frame_config, - unix_time=unix_time, - target_labels=self.target_labels, ) if len(self.frame_results) > 0: diff --git a/perception_eval/perception_eval/result/perception/perception_frame_result.py b/perception_eval/perception_eval/result/perception/perception_frame_result.py index ce862f80..8f752e6c 100644 --- a/perception_eval/perception_eval/result/perception/perception_frame_result.py +++ b/perception_eval/perception_eval/result/perception/perception_frame_result.py @@ -60,38 +60,45 @@ class PerceptionFrameResult: def __init__( self, + unix_time: int, + frame_config: PerceptionFrameConfig, + metrics_config: MetricsScoreConfig, object_results: List[DynamicObjectWithPerceptionResult], frame_ground_truth: FrameGroundTruth, - metrics_config: MetricsScoreConfig, - frame_config: PerceptionFrameConfig, - unix_time: int, - target_labels: List[LabelType], ) -> None: - self.frame_number = frame_ground_truth.frame_number self.unix_time = unix_time - self.target_labels = target_labels + self.frame_config = frame_config + self.metrics_config = metrics_config self.object_results = object_results self.frame_ground_truth = frame_ground_truth # init evaluation self.metrics_score = metrics.MetricsScore( - metrics_config, + self.metrics_config, used_frame=[int(self.frame_number)], ) self.pass_fail_result = PassFailResult( - unix_time=unix_time, + unix_time=self.unix_time, frame_number=self.frame_number, - frame_config=frame_config, - ego2map=frame_ground_truth.ego2map, + frame_config=self.frame_config, + ego2map=self.frame_ground_truth.ego2map, ) + @property + def target_labels(self) -> List[LabelType]: + return self.frame_config.target_labels + + @property + def frame_number(self) -> int: + return self.frame_ground_truth.frame_number + def evaluate_frame( self, critical_ground_truth_objects: List[ObjectType], previous_result: Optional[PerceptionFrameResult] = None, ) -> None: - """[summary] + """ Evaluate a frame from the pair of estimated objects and ground truth objects Args: ros_critical_ground_truth_objects (List[ObjectType]): The list of Ground truth objects filtered by ROS node.