From c7d6a509f7a586bf39ee8c14dcdc29728b247231 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Grzegorz=20G=C5=82owacki?= Date: Wed, 30 Oct 2024 11:42:25 +0000 Subject: [PATCH 1/5] shallow copy instead of deepcopy --- .../perception_eval/evaluation/matching/objects_filter.py | 6 +++--- perception_eval/perception_eval/tool/utils.py | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index eab315a0..11bd8235 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -32,7 +32,7 @@ from perception_eval.common.transform import TransformDict from perception_eval.evaluation import DynamicObjectWithPerceptionResult from perception_eval.evaluation.matching import MatchingMode - +from copy import copy def filter_object_results( object_results: List[DynamicObjectWithPerceptionResult], @@ -123,7 +123,7 @@ def filter_object_results( is_target = False if is_target: - filtered_object_results.append(object_result) + filtered_object_results.append(copy(object_result)) return filtered_object_results @@ -198,7 +198,7 @@ def filter_objects( transforms=transforms, ) if is_target: - filtered_objects.append(object_) + filtered_objects.append(copy(object_)) return filtered_objects diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index 0c1c4e23..c4ad3ff1 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -14,7 +14,7 @@ from __future__ import annotations -from copy import deepcopy +from copy import deepcopy, copy from enum import Enum from typing import Any from typing import Dict @@ -475,7 +475,7 @@ def filter_frame_by_distance( Returns: PerceptionFrameResult: Filtered frame results. """ - ret_frame = deepcopy(frame) + ret_frame = copy(frame) if min_distance is not None: min_distance_list = [min_distance] * len(ret_frame.target_labels) From c7cbc48af7f5105c723c004dfb380b68e5650f4d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Grzegorz=20G=C5=82owacki?= Date: Thu, 7 Nov 2024 16:12:07 +0000 Subject: [PATCH 2/5] fixes for isort --- .../perception_eval/evaluation/matching/objects_filter.py | 3 ++- perception_eval/perception_eval/tool/utils.py | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index 11bd8235..3a82f539 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -12,6 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. +from copy import copy from typing import Dict from typing import List from typing import Optional @@ -32,7 +33,7 @@ from perception_eval.common.transform import TransformDict from perception_eval.evaluation import DynamicObjectWithPerceptionResult from perception_eval.evaluation.matching import MatchingMode -from copy import copy + def filter_object_results( object_results: List[DynamicObjectWithPerceptionResult], diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index c4ad3ff1..a9640535 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -14,7 +14,8 @@ from __future__ import annotations -from copy import deepcopy, copy +from copy import copy +from copy import deepcopy from enum import Enum from typing import Any from typing import Dict From e0c5c4b256b5eb6b618607535582669978960b42 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Grzegorz=20G=C5=82owacki?= Date: Mon, 18 Nov 2024 13:39:39 +0000 Subject: [PATCH 3/5] shallow copy of required fields. --- .../result/perception_frame_result.py | 19 ++++++++++++++++++- perception_eval/perception_eval/tool/utils.py | 2 +- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/perception_frame_result.py b/perception_eval/perception_eval/evaluation/result/perception_frame_result.py index 0d9b5a08..9925fa01 100644 --- a/perception_eval/perception_eval/evaluation/result/perception_frame_result.py +++ b/perception_eval/perception_eval/evaluation/result/perception_frame_result.py @@ -13,7 +13,7 @@ # limitations under the License. from __future__ import annotations - +from copy import copy from typing import Dict from typing import List from typing import Optional @@ -89,6 +89,23 @@ def __init__( transforms=frame_ground_truth.transforms, ) + def copy_with_shallow_results(self) -> PerceptionFrameResult: + """ + Create a shallow copy of the current PerceptionFrameResult instance. + + This method creates a new instance of PerceptionFrameResult by performing a shallow copy + of the current instance. The `metrics_score` and `pass_fail_result` attributes are also + shallow copied to the new instance. + + Returns: + PerceptionFrameResult: A new instance of PerceptionFrameResult with shallow copied attributes. + """ + + new_instance = copy(self) + new_instance.metrics_score = copy(self.metrics_score) + new_instance.pass_fail_result = copy(self.pass_fail_result) + return new_instance + def evaluate_frame( self, previous_result: Optional[PerceptionFrameResult] = None, diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index a9640535..a526248a 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -476,7 +476,7 @@ def filter_frame_by_distance( Returns: PerceptionFrameResult: Filtered frame results. """ - ret_frame = copy(frame) + ret_frame = frame.copy_with_shallow_results() if min_distance is not None: min_distance_list = [min_distance] * len(ret_frame.target_labels) From 968d12f29254da8a1691297401c5a19262fcca9e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Grzegorz=20G=C5=82owacki?= Date: Mon, 18 Nov 2024 13:44:49 +0000 Subject: [PATCH 4/5] unused import --- perception_eval/perception_eval/tool/utils.py | 1 - 1 file changed, 1 deletion(-) diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index a526248a..32cc6a70 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -14,7 +14,6 @@ from __future__ import annotations -from copy import copy from copy import deepcopy from enum import Enum from typing import Any From ce04d9fd676167d1c9bb14c8cc5731f24e287316 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Grzegorz=20G=C5=82owacki?= Date: Thu, 21 Nov 2024 13:56:13 +0000 Subject: [PATCH 5/5] deepcopy with sharing --- .../perception_eval/common/deepcopy.py | 38 +++++++++++++++++++ .../evaluation/result/object_result.py | 4 ++ .../result/perception_frame_result.py | 19 +--------- perception_eval/perception_eval/tool/utils.py | 3 +- 4 files changed, 44 insertions(+), 20 deletions(-) create mode 100644 perception_eval/perception_eval/common/deepcopy.py diff --git a/perception_eval/perception_eval/common/deepcopy.py b/perception_eval/perception_eval/common/deepcopy.py new file mode 100644 index 00000000..5ab4cbe4 --- /dev/null +++ b/perception_eval/perception_eval/common/deepcopy.py @@ -0,0 +1,38 @@ +from copy import deepcopy + + +# https://stackoverflow.com/a/24621200/4732868 +def deepcopy_with_sharing(obj, shared_attribute_names, memo=None): + """ + Deepcopy an object, except for a given list of attributes, which should + be shared between the original object and its copy. + + obj is some object + shared_attribute_names: A list of strings identifying the attributes that + should be shared between the original and its copy. + memo is the dictionary passed into __deepcopy__. Ignore this argument if + not calling from within __deepcopy__. + """ + assert isinstance(shared_attribute_names, (list, tuple)) + shared_attributes = {k: getattr(obj, k) for k in shared_attribute_names} + + if hasattr(obj, "__deepcopy__"): + # Do hack to prevent infinite recursion in call to deepcopy + deepcopy_method = obj.__deepcopy__ + obj.__deepcopy__ = None + + for attr in shared_attribute_names: + del obj.__dict__[attr] + + clone = deepcopy(obj) + + for attr, val in shared_attributes.items(): + setattr(obj, attr, val) + setattr(clone, attr, val) + + if hasattr(obj, "__deepcopy__"): + # Undo hack + obj.__deepcopy__ = deepcopy_method + del clone.__deepcopy__ + + return clone diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index d4c6e9df..6adf39d2 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -25,6 +25,7 @@ from perception_eval.common import DynamicObject from perception_eval.common import DynamicObject2D from perception_eval.common import ObjectType +from perception_eval.common.deepcopy import deepcopy_with_sharing from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.common.label import LabelType from perception_eval.common.label import TrafficLightLabel @@ -106,6 +107,9 @@ def __init__( self.iou_3d = None self.plane_distance = None + def __deepcopy__(self, memo): + return deepcopy_with_sharing(self, shared_attribute_names = ['estimated_object', 'ground_truth_object'], memo=memo) + def get_status( self, matching_mode: MatchingMode, diff --git a/perception_eval/perception_eval/evaluation/result/perception_frame_result.py b/perception_eval/perception_eval/evaluation/result/perception_frame_result.py index 9925fa01..373b64a3 100644 --- a/perception_eval/perception_eval/evaluation/result/perception_frame_result.py +++ b/perception_eval/perception_eval/evaluation/result/perception_frame_result.py @@ -13,7 +13,7 @@ # limitations under the License. from __future__ import annotations -from copy import copy +from copy import copy, deepcopy from typing import Dict from typing import List from typing import Optional @@ -89,23 +89,6 @@ def __init__( transforms=frame_ground_truth.transforms, ) - def copy_with_shallow_results(self) -> PerceptionFrameResult: - """ - Create a shallow copy of the current PerceptionFrameResult instance. - - This method creates a new instance of PerceptionFrameResult by performing a shallow copy - of the current instance. The `metrics_score` and `pass_fail_result` attributes are also - shallow copied to the new instance. - - Returns: - PerceptionFrameResult: A new instance of PerceptionFrameResult with shallow copied attributes. - """ - - new_instance = copy(self) - new_instance.metrics_score = copy(self.metrics_score) - new_instance.pass_fail_result = copy(self.pass_fail_result) - return new_instance - def evaluate_frame( self, previous_result: Optional[PerceptionFrameResult] = None, diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index 32cc6a70..3c7ab2df 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -475,8 +475,7 @@ def filter_frame_by_distance( Returns: PerceptionFrameResult: Filtered frame results. """ - ret_frame = frame.copy_with_shallow_results() - + ret_frame = deepcopy(frame) if min_distance is not None: min_distance_list = [min_distance] * len(ret_frame.target_labels) else: