From 8896556a47d91abc6acd546740d4fc4fa149157f Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Wed, 18 Dec 2024 23:17:43 +0900 Subject: [PATCH 01/13] fundamental commit Signed-off-by: MasatoSaeki --- .../criteria/perception.py | 25 +++++++++++------ .../driving_log_replayer_v2/perception.py | 28 ++++++++++++++++++- 2 files changed, 43 insertions(+), 10 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py index f167f149..506fb2d6 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py @@ -25,10 +25,11 @@ import numpy as np from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.evaluation.matching import MatchingMode -from perception_eval.tool.utils import filter_frame_by_distance +from perception_eval.tool.utils import filter_frame_by_distance, filter_frame_by_region if TYPE_CHECKING: from perception_eval.evaluation import PerceptionFrameResult + from driving_log_replayer_v2.perception import Filter class SuccessFail(Enum): @@ -471,8 +472,9 @@ def is_error(self) -> bool: class CriteriaFilter: - def __init__(self, distance_range: tuple[Number, Number] | None = None) -> None: - self.distance_range = distance_range + def __init__(self, filter: Filter | None = None) -> None: + self.distance_range = getattr(filter, "Distance", None) + self.region = getattr(filter, "Region", None) def is_all_none(self) -> bool: """ @@ -483,7 +485,7 @@ def is_all_none(self) -> bool: bool: True if all filter params are None. """ - return self.distance_range is None + return self.distance_range is None and self.region is None def filter_frame_result(self, frame: PerceptionFrameResult) -> PerceptionFrameResult: """ @@ -500,10 +502,15 @@ def filter_frame_result(self, frame: PerceptionFrameResult) -> PerceptionFrameRe PerceptionFrameResult: Filtered result. """ - if self.is_all_none() or self.distance_range is None: + if self.is_all_none(): return frame - min_distance, max_distance = self.distance_range - return filter_frame_by_distance(frame, min_distance, max_distance) + if self.distance_range is not None: + min_distance, max_distance = self.distance_range + return filter_frame_by_distance(frame, min_distance, max_distance) + if self.region is not None: + axis_x: tuple[Number, Number] = self.region.axis_x + axis_y: tuple[Number, Number] = self.region.axis_y + return filter_frame_by_region(frame, axis_x, axis_y) class PerceptionCriteria: @@ -526,7 +533,7 @@ def __init__( # noqa: C901 levels: ( str | list[str] | Number | list[Number] | CriteriaLevel | list[CriteriaLevel] | None ) = None, - distance_range: tuple[Number, Number] | None = None, + filter: Filter | None = None, ) -> None: methods = [CriteriaMethod.NUM_TP] if methods is None else self.load_methods(methods) levels = [CriteriaLevel.EASY] if levels is None else self.load_levels(levels) @@ -558,7 +565,7 @@ def __init__( # noqa: C901 error_msg: str = f"Unsupported method: {method}" raise NotImplementedError(error_msg) - self.criteria_filter = CriteriaFilter(distance_range) + self.criteria_filter = CriteriaFilter(filter) @staticmethod def load_methods( diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index f9e5dcb0..63250379 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -33,8 +33,34 @@ from driving_log_replayer_v2.scenario import Scenario +class Region(BaseModel): + axis_x: tuple[float, float] + axis_y: tuple[float, float] + + @field_validator("axis_x, axis_y", mode="before") + @classmethod + def validate_area_range(cls, v: dict | None) -> tuple[number, number] | None: + if v is None: + return None + + err_msg = f"{v} is not valid distance range, expected ordering min-max with min < max." + + s_lower, s_upper = v.split("-") + if s_upper == "": + s_upper = sys.float_info.max + + lower = float(s_lower) + upper = float(s_upper) + + if lower >= upper: + raise ValueError(err_msg) + + return (lower, upper) + + class Filter(BaseModel): Distance: tuple[float, float] | None = None + Region: Region | None = None # add filter condition here @field_validator("Distance", mode="before") @@ -106,7 +132,7 @@ def __post_init__(self) -> None: self.criteria = PerceptionCriteria( methods=self.condition.CriteriaMethod, levels=self.condition.CriteriaLevel, - distance_range=self.condition.Filter.Distance, + filters=self.condition.Filter, ) def set_frame(self, frame: PerceptionFrameResult) -> dict: From 3c0716c60681e570f2a75248cbdf4801555f4de4 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Thu, 19 Dec 2024 01:45:57 +0900 Subject: [PATCH 02/13] fix Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/criteria/perception.py | 8 ++++---- .../driving_log_replayer_v2/perception.py | 12 ++++++------ 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py index 506fb2d6..743b4726 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py @@ -508,9 +508,9 @@ def filter_frame_result(self, frame: PerceptionFrameResult) -> PerceptionFrameRe min_distance, max_distance = self.distance_range return filter_frame_by_distance(frame, min_distance, max_distance) if self.region is not None: - axis_x: tuple[Number, Number] = self.region.axis_x - axis_y: tuple[Number, Number] = self.region.axis_y - return filter_frame_by_region(frame, axis_x, axis_y) + x_position: tuple[Number, Number] = self.region.x_position + y_position: tuple[Number, Number] = self.region.y_position + return filter_frame_by_region(frame, x_position, y_position) class PerceptionCriteria: @@ -533,7 +533,7 @@ def __init__( # noqa: C901 levels: ( str | list[str] | Number | list[Number] | CriteriaLevel | list[CriteriaLevel] | None ) = None, - filter: Filter | None = None, + filters: Filter | None = None, ) -> None: methods = [CriteriaMethod.NUM_TP] if methods is None else self.load_methods(methods) levels = [CriteriaLevel.EASY] if levels is None else self.load_levels(levels) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 63250379..79f90560 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -34,18 +34,18 @@ class Region(BaseModel): - axis_x: tuple[float, float] - axis_y: tuple[float, float] + x_position: tuple[float, float] | None = None + y_position: tuple[float, float] | None = None - @field_validator("axis_x, axis_y", mode="before") + @field_validator("x_position", "y_position", mode="before") @classmethod - def validate_area_range(cls, v: dict | None) -> tuple[number, number] | None: + def validate_region_range(cls, v: float | None) -> float | None: if v is None: return None err_msg = f"{v} is not valid distance range, expected ordering min-max with min < max." - s_lower, s_upper = v.split("-") + s_lower, s_upper = v.split(",") if s_upper == "": s_upper = sys.float_info.max @@ -60,7 +60,7 @@ def validate_area_range(cls, v: dict | None) -> tuple[number, number] | None: class Filter(BaseModel): Distance: tuple[float, float] | None = None - Region: Region | None = None + Region: Region # add filter condition here @field_validator("Distance", mode="before") From d650afacfd8c2b87d3da78099e31337542fe9a3d Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Thu, 19 Dec 2024 15:20:49 +0900 Subject: [PATCH 03/13] fix bug Signed-off-by: MasatoSaeki --- .../criteria/perception.py | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py index 743b4726..8e5bdd98 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py @@ -25,10 +25,12 @@ import numpy as np from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.evaluation.matching import MatchingMode -from perception_eval.tool.utils import filter_frame_by_distance, filter_frame_by_region +from perception_eval.tool.utils import filter_frame_by_distance +from perception_eval.tool.utils import filter_frame_by_region if TYPE_CHECKING: from perception_eval.evaluation import PerceptionFrameResult + from driving_log_replayer_v2.perception import Filter @@ -472,9 +474,9 @@ def is_error(self) -> bool: class CriteriaFilter: - def __init__(self, filter: Filter | None = None) -> None: - self.distance_range = getattr(filter, "Distance", None) - self.region = getattr(filter, "Region", None) + def __init__(self, filters: Filter | None = None) -> None: + self.distance_range = getattr(filters, "Distance", None) + self.region = getattr(filters, "Region", None) def is_all_none(self) -> bool: """ @@ -511,6 +513,8 @@ def filter_frame_result(self, frame: PerceptionFrameResult) -> PerceptionFrameRe x_position: tuple[Number, Number] = self.region.x_position y_position: tuple[Number, Number] = self.region.y_position return filter_frame_by_region(frame, x_position, y_position) + error_msg = "only select one filter condition" + raise ValueError(error_msg) class PerceptionCriteria: @@ -523,7 +527,7 @@ class PerceptionCriteria: If None, `CriteriaMethod.NUM_TP` is used. Defaults to None. levels (str | list[str] | Number | list[Number] | CriteriaLevel | list[CriteriaLevel]): Criteria level instance or name. If None, `CriteriaLevel.Easy` is used. Defaults to None. - distance_range (tuple[Number, Number] | None): Range of distance to filter frame result. Defaults to None. + filters (Filter | None): Filter instance. Defaults to None. """ @@ -565,7 +569,7 @@ def __init__( # noqa: C901 error_msg: str = f"Unsupported method: {method}" raise NotImplementedError(error_msg) - self.criteria_filter = CriteriaFilter(filter) + self.criteria_filter = CriteriaFilter(filters) @staticmethod def load_methods( From a49f4c1ca8bedf6ad2f11a55fcb556e64c141ae9 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Thu, 19 Dec 2024 16:19:23 +0900 Subject: [PATCH 04/13] add validator Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/perception.py | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 79f90560..9c8b4240 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -12,17 +12,23 @@ # See the License for the specific language governing permissions and # limitations under the License. +from __future__ import annotations + from dataclasses import dataclass import sys from typing import Literal +from typing import TYPE_CHECKING -from perception_eval.evaluation import PerceptionFrameResult from pydantic import BaseModel from pydantic import field_validator +from pydantic import model_validator from std_msgs.msg import ColorRGBA from std_msgs.msg import Header from visualization_msgs.msg import MarkerArray +if TYPE_CHECKING: + from perception_eval.evaluation import PerceptionFrameResult + from driving_log_replayer_v2.criteria import PerceptionCriteria import driving_log_replayer_v2.perception_eval_conversions as eval_conversions from driving_log_replayer_v2.perception_eval_conversions import FrameDescriptionWriter @@ -82,6 +88,13 @@ def validate_distance_range(cls, v: str | None) -> tuple[number, number] | None: raise ValueError(err_msg) return (lower, upper) + @model_validator(mode="after") + def validate_duplicate_filter(self) -> Filter: + if self.Distance is not None and self.Region is not None: + error_msg = "Distance and Region filter cannot be used at the same time." + raise ValueError(error_msg) + return self + class Criteria(BaseModel): PassRate: number From 27f8090620bc2c0a48203305798e31d69765df07 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Thu, 19 Dec 2024 17:50:32 +0900 Subject: [PATCH 05/13] fix validation Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/perception.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 9c8b4240..8e010233 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -45,28 +45,29 @@ class Region(BaseModel): @field_validator("x_position", "y_position", mode="before") @classmethod - def validate_region_range(cls, v: float | None) -> float | None: + def validate_region_range(cls, v: str | None) -> tuple[number, number] | None: if v is None: return None - err_msg = f"{v} is not valid distance range, expected ordering min-max with min < max." + err_non_specify_msg = "both min and max values must be specified." + err_range_msg = f"{v} is not valid distance range, expected ordering min-max with min < max." s_lower, s_upper = v.split(",") - if s_upper == "": - s_upper = sys.float_info.max + + assert s_upper != "" and s_lower != "", err_non_specify_msg lower = float(s_lower) upper = float(s_upper) if lower >= upper: - raise ValueError(err_msg) + raise ValueError(err_range_msg) return (lower, upper) class Filter(BaseModel): Distance: tuple[float, float] | None = None - Region: Region + Region: Region | None # add filter condition here @field_validator("Distance", mode="before") From 6a74a344516b9910c1639ab53e84d5488d6a3bb3 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Thu, 19 Dec 2024 23:37:28 +0900 Subject: [PATCH 06/13] set default value Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/perception.py | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 8e010233..d0c45a8d 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -89,6 +89,22 @@ def validate_distance_range(cls, v: str | None) -> tuple[number, number] | None: raise ValueError(err_msg) return (lower, upper) + @field_validator("Region", mode="after") + @classmethod + def validate_region_value(cls, v: Region | None) -> Region | None: + if v is None: + return None + if v.x_position is None and v.y_position is None: + return None + return v + + @model_validator(mode="before") + @classmethod + def set_region_default_value(cls, v: dict) -> dict: + if "Region" not in v: + v["Region"] = None + return v + @model_validator(mode="after") def validate_duplicate_filter(self) -> Filter: if self.Distance is not None and self.Region is not None: From 4deb845f048bad13d2067c483af82dc127168f49 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Fri, 20 Dec 2024 01:12:33 +0900 Subject: [PATCH 07/13] add sample Signed-off-by: MasatoSaeki --- sample/perception/scenario.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/sample/perception/scenario.yaml b/sample/perception/scenario.yaml index ae1ec1d6..c8a55abe 100644 --- a/sample/perception/scenario.yaml +++ b/sample/perception/scenario.yaml @@ -16,11 +16,17 @@ Evaluation: CriteriaLevel: hard # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0. For error criteria, set custom value.) Filter: Distance: 0.0-50.0 # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. CriteriaMethod: num_gt_tp # Method name of criteria (num_tp/metrics_score/metrics_score_mph/label/velocity_x_error/velocity_y_error/speed_error/yaw_error) CriteriaLevel: easy # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0. For error criteria, set custom value.) Filter: Distance: 50.0- # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] PerceptionEvaluationConfig: evaluation_config_dict: evaluation_task: detection # detection or tracking. Evaluate the objects specified here From 8e23b11108b8253323380d6392beeac1f1d0b49a Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Fri, 20 Dec 2024 09:08:43 +0900 Subject: [PATCH 08/13] fix validate and run pre-commit Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/perception.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index d0c45a8d..264316e9 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -50,11 +50,14 @@ def validate_region_range(cls, v: str | None) -> tuple[number, number] | None: return None err_non_specify_msg = "both min and max values must be specified." - err_range_msg = f"{v} is not valid distance range, expected ordering min-max with min < max." + err_range_msg = ( + f"{v} is not valid distance range, expected ordering min-max with min < max." + ) s_lower, s_upper = v.split(",") - - assert s_upper != "" and s_lower != "", err_non_specify_msg + + if s_upper != "" or s_lower != "": + raise ValueError(err_non_specify_msg) lower = float(s_lower) upper = float(s_upper) From 753af7d31cc46135cd3e0a536c753597d6e85e33 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Mon, 23 Dec 2024 09:35:59 +0900 Subject: [PATCH 09/13] fix check algo Signed-off-by: MasatoSaeki --- driving_log_replayer_v2/driving_log_replayer_v2/perception.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 264316e9..176eb130 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -56,7 +56,7 @@ def validate_region_range(cls, v: str | None) -> tuple[number, number] | None: s_lower, s_upper = v.split(",") - if s_upper != "" or s_lower != "": + if s_upper == "" or s_lower == "": raise ValueError(err_non_specify_msg) lower = float(s_lower) From cd1e5a2fb00e30ab4d52bfb0acaa2962c48e3138 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Mon, 23 Dec 2024 10:31:05 +0900 Subject: [PATCH 10/13] fix docs Signed-off-by: MasatoSaeki --- sample/perception/scenario.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/sample/perception/scenario.yaml b/sample/perception/scenario.yaml index c8a55abe..f855adf4 100644 --- a/sample/perception/scenario.yaml +++ b/sample/perception/scenario.yaml @@ -17,16 +17,16 @@ Evaluation: Filter: Distance: 0.0-50.0 # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] Region: - x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] - y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. CriteriaMethod: num_gt_tp # Method name of criteria (num_tp/metrics_score/metrics_score_mph/label/velocity_x_error/velocity_y_error/speed_error/yaw_error) CriteriaLevel: easy # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0. For error criteria, set custom value.) Filter: Distance: 50.0- # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] Region: - x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] - y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] PerceptionEvaluationConfig: evaluation_config_dict: evaluation_task: detection # detection or tracking. Evaluate the objects specified here From a8fec3503234467ffbea429974d6a18d7903c020 Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Wed, 25 Dec 2024 11:51:56 +0900 Subject: [PATCH 11/13] adopt it for traffic light Signed-off-by: MasatoSaeki --- .../driving_log_replayer_v2/traffic_light.py | 62 ++++++++++++++++++- sample/traffic_light/scenario.ja.yaml | 8 ++- sample/traffic_light/scenario.yaml | 7 +++ 3 files changed, 75 insertions(+), 2 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py b/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py index 692a1461..16e7f729 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py @@ -12,18 +12,25 @@ # See the License for the specific language governing permissions and # limitations under the License. +from __future__ import annotations + from dataclasses import dataclass import logging from pathlib import Path import sys from typing import Literal +from typing import TYPE_CHECKING from autoware_perception_msgs.msg import TrafficSignalElement from perception_eval.evaluation import PerceptionFrameResult from pydantic import BaseModel from pydantic import field_validator +from pydantic import model_validator import simplejson as json +if TYPE_CHECKING: + from perception_eval.evaluation import PerceptionFrameResult + from driving_log_replayer_v2.criteria import PerceptionCriteria from driving_log_replayer_v2.perception_eval_conversions import summarize_pass_fail_result from driving_log_replayer_v2.result import EvaluationItem @@ -101,8 +108,38 @@ def get_most_probable_element( return elements[index] +class Region(BaseModel): + x_position: tuple[float, float] | None = None + y_position: tuple[float, float] | None = None + + @field_validator("x_position", "y_position", mode="before") + @classmethod + def validate_region_range(cls, v: str | None) -> tuple[number, number] | None: + if v is None: + return None + + err_non_specify_msg = "both min and max values must be specified." + err_range_msg = ( + f"{v} is not valid distance range, expected ordering min-max with min < max." + ) + + s_lower, s_upper = v.split(",") + + if s_upper != "" or s_lower != "": + raise ValueError(err_non_specify_msg) + + lower = float(s_lower) + upper = float(s_upper) + + if lower >= upper: + raise ValueError(err_range_msg) + + return (lower, upper) + + class Filter(BaseModel): Distance: tuple[float, float] | None = None + Region: Region | None # add filter condition here @field_validator("Distance", mode="before") @@ -124,6 +161,29 @@ def validate_distance_range(cls, v: str | None) -> tuple[number, number] | None: raise ValueError(err_msg) return (lower, upper) + @field_validator("Region", mode="after") + @classmethod + def validate_region_value(cls, v: Region | None) -> Region | None: + if v is None: + return None + if v.x_position is None and v.y_position is None: + return None + return v + + @model_validator(mode="before") + @classmethod + def set_region_default_value(cls, v: dict) -> dict: + if "Region" not in v: + v["Region"] = None + return v + + @model_validator(mode="after") + def validate_duplicate_filter(self) -> Filter: + if self.Distance is not None and self.Region is not None: + error_msg = "Distance and Region filter cannot be used at the same time." + raise ValueError(error_msg) + return self + class Criteria(BaseModel): PassRate: number @@ -194,7 +254,7 @@ def __post_init__(self) -> None: self.criteria: PerceptionCriteria = PerceptionCriteria( methods=self.condition.CriteriaMethod, levels=self.condition.CriteriaLevel, - distance_range=self.condition.Filter.Distance, + filters=self.condition.Filter, ) def set_frame(self, frame: PerceptionFrameResult) -> dict: diff --git a/sample/traffic_light/scenario.ja.yaml b/sample/traffic_light/scenario.ja.yaml index f472ff0b..66cd895a 100644 --- a/sample/traffic_light/scenario.ja.yaml +++ b/sample/traffic_light/scenario.ja.yaml @@ -9,7 +9,6 @@ Evaluation: Datasets: - sample: VehicleId: "7" # データセット毎にVehicleIdを指定する - Conditions: Criterion: - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. @@ -17,11 +16,17 @@ Evaluation: CriteriaLevel: hard # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0) Filter: Distance: 0.0-50.0 # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. CriteriaMethod: num_gt_tp # refer https://github.com/tier4/driving_log_replayer_v2/blob/develop/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py#L136-L152 CriteriaLevel: easy # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0) Filter: Distance: 50.0- # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] PerceptionEvaluationConfig: camera_type: cam_traffic_light_near # 信号認識のカメラタイプを指定する evaluation_config_dict: @@ -31,6 +36,7 @@ Evaluation: min_distance: 0.0 # 評価対象の信号機の最小距離 allow_matching_unknown: true # ラベルがunknownのオブジェクトとマッチングさせるか merge_similar_labels: false # 類似のラベルをマージするか https://github.com/tier4/autoware_perception_evaluation/blob/develop/docs/ja/perception/label.md#%E9%A1%9E%E4%BC%BC%E3%83%A9%E3%83%99%E3%83%AB%E3%81%AE%E3%83%9E%E3%83%BC%E3%82%B8 + uuid_matching_first: false # 最初にUUIDでマッチングさせるか CriticalObjectFilterConfig: target_labels: [green, red, yellow, unknown] PerceptionPassFailConfig: diff --git a/sample/traffic_light/scenario.yaml b/sample/traffic_light/scenario.yaml index d2f57057..c80cae71 100644 --- a/sample/traffic_light/scenario.yaml +++ b/sample/traffic_light/scenario.yaml @@ -16,11 +16,17 @@ Evaluation: CriteriaLevel: hard # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0) Filter: Distance: 0.0-50.0 # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. CriteriaMethod: num_gt_tp # refer https://github.com/tier4/driving_log_replayer_v2/blob/develop/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py#L136-L152 CriteriaLevel: easy # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0) Filter: Distance: 50.0- # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] + Region: + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] PerceptionEvaluationConfig: camera_type: cam_traffic_light_near # Specifies the type of camera for traffic_light. evaluation_config_dict: @@ -30,6 +36,7 @@ Evaluation: min_distance: 0.0 # Maximum distance of traffic lights to be evaluated allow_matching_unknown: true # Whether or not to match objects whose labels are unknown merge_similar_labels: false # Whether or not to merge similar labels https://github.com/tier4/autoware_perception_evaluation/blob/develop/docs/en/perception/label.md#merge-similar-labels-option + uuid_matching_first: false # Whether or not to match by UUID first CriticalObjectFilterConfig: target_labels: [green, red, yellow, unknown] PerceptionPassFailConfig: From e4ae6c24e9a6e8c145227d1129538ac5990712ae Mon Sep 17 00:00:00 2001 From: MasatoSaeki Date: Wed, 25 Dec 2024 11:57:20 +0900 Subject: [PATCH 12/13] fix sample scenario file Signed-off-by: MasatoSaeki --- sample/perception/scenario.ja.yaml | 6 ++++++ sample/perception/scenario.yaml | 8 ++++---- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/sample/perception/scenario.ja.yaml b/sample/perception/scenario.ja.yaml index ead9dd03..6d68c531 100644 --- a/sample/perception/scenario.ja.yaml +++ b/sample/perception/scenario.ja.yaml @@ -16,11 +16,17 @@ Evaluation: CriteriaLevel: hard # クライテリアレベル(perfect/hard/normal/easy、もしくはカスタム値0.0〜100.0の数値でエラーの場合は許容誤差を指定。) Filter: Distance: 0.0-50.0 # [m] null [距離でフィルタしない] or 下限-(上限) [上限は省略可。省略した場合1.7976931348623157e+308] + Region: + x_position: null # [m] null [x座標でフィルタしない] or 下限,上限 + y_position: null # [m] null [y座標でフィルタしない] or 下限,上限 - PassRate: 95.0 # 評価試行回数の内、どの程度(%)評価成功だったら成功とするか CriteriaMethod: num_gt_tp # refer https://github.com/tier4/driving_log_replayer_v2/blob/develop/driving_log_replayer_v2/driving_log_replayer_v2/criteria/perception.py#L136-L152 CriteriaLevel: easy # クライテリアレベル(perfect/hard/normal/easy、もしくはカスタム値0.0〜100.0の数値でエラーの場合は許容誤差を指定。) Filter: Distance: 50.0- # [m] null [距離でフィルタしない] or 下限-(上限) [上限は省略可。省略した場合1.7976931348623157e+308] + Region: + x_position: null # [m] null [x座標でフィルタしない] or 下限,上限 + y_position: null # [m] null [y座標でフィルタしない] or 下限,上限 PerceptionEvaluationConfig: evaluation_config_dict: evaluation_task: detection # detection/tracking ここで指定したobjectsを評価する diff --git a/sample/perception/scenario.yaml b/sample/perception/scenario.yaml index f855adf4..209be32b 100644 --- a/sample/perception/scenario.yaml +++ b/sample/perception/scenario.yaml @@ -17,16 +17,16 @@ Evaluation: Filter: Distance: 0.0-50.0 # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] Region: - x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] - y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit - PassRate: 95.0 # How much (%) of the evaluation attempts are considered successful. CriteriaMethod: num_gt_tp # Method name of criteria (num_tp/metrics_score/metrics_score_mph/label/velocity_x_error/velocity_y_error/speed_error/yaw_error) CriteriaLevel: easy # Level of criteria (perfect/hard/normal/easy, or custom value 0.0-100.0. For error criteria, set custom value.) Filter: Distance: 50.0- # [m] null [Do not filter by distance] or lower_limit-(upper_limit) [Upper limit can be omitted. If omitted value is 1.7976931348623157e+308] Region: - x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] - y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit [Lower and upper limit can be omitted. If omitted value is +-1.7976931348623157e+308] + x_position: null # [m] null [Do not filter by x_position] or lower_limit,upper_limit + y_position: null # [m] null [Do not filter by y_position] or lower_limit,upper_limit PerceptionEvaluationConfig: evaluation_config_dict: evaluation_task: detection # detection or tracking. Evaluate the objects specified here From 7c17ab5d2baf002c42335a3c4e5574ae885a4cf9 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 25 Dec 2024 12:31:29 +0900 Subject: [PATCH 13/13] chore: update UseCaseFormatVersion of perception and traffic_light Signed-off-by: Hayato Mizushima --- driving_log_replayer_v2/driving_log_replayer_v2/perception.py | 2 +- .../driving_log_replayer_v2/traffic_light.py | 2 +- sample/perception/scenario.ja.yaml | 2 +- sample/perception/scenario.yaml | 2 +- sample/traffic_light/scenario.ja.yaml | 2 +- sample/traffic_light/scenario.yaml | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py index 176eb130..7450a809 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/perception.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/perception.py @@ -145,7 +145,7 @@ class Conditions(BaseModel): class Evaluation(BaseModel): UseCaseName: Literal["perception"] - UseCaseFormatVersion: Literal["1.0.0"] + UseCaseFormatVersion: Literal["1.0.0", "1.1.0"] Datasets: list[dict] Conditions: Conditions PerceptionEvaluationConfig: dict diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py b/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py index 16e7f729..0df6408c 100644 --- a/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py +++ b/driving_log_replayer_v2/driving_log_replayer_v2/traffic_light.py @@ -202,7 +202,7 @@ class Conditions(BaseModel): class Evaluation(BaseModel): UseCaseName: Literal["traffic_light"] - UseCaseFormatVersion: Literal["1.0.0"] + UseCaseFormatVersion: Literal["1.0.0", "1.1.0"] Datasets: list[dict] Conditions: Conditions PerceptionEvaluationConfig: dict diff --git a/sample/perception/scenario.ja.yaml b/sample/perception/scenario.ja.yaml index 6d68c531..161349cb 100644 --- a/sample/perception/scenario.ja.yaml +++ b/sample/perception/scenario.ja.yaml @@ -5,7 +5,7 @@ SensorModel: sample_sensor_kit VehicleModel: sample_vehicle Evaluation: UseCaseName: perception - UseCaseFormatVersion: 1.0.0 + UseCaseFormatVersion: 1.1.0 Datasets: - sample_dataset: VehicleId: default # データセット毎にVehicleIdを指定する diff --git a/sample/perception/scenario.yaml b/sample/perception/scenario.yaml index 209be32b..c63ddca2 100644 --- a/sample/perception/scenario.yaml +++ b/sample/perception/scenario.yaml @@ -5,7 +5,7 @@ SensorModel: sample_sensor_kit VehicleModel: sample_vehicle Evaluation: UseCaseName: perception - UseCaseFormatVersion: 1.0.0 + UseCaseFormatVersion: 1.1.0 Datasets: - sample_dataset: VehicleId: default # Specify VehicleId for each data set. diff --git a/sample/traffic_light/scenario.ja.yaml b/sample/traffic_light/scenario.ja.yaml index 66cd895a..9c3a705a 100644 --- a/sample/traffic_light/scenario.ja.yaml +++ b/sample/traffic_light/scenario.ja.yaml @@ -5,7 +5,7 @@ SensorModel: aip_xx1 VehicleModel: jpntaxi Evaluation: UseCaseName: traffic_light - UseCaseFormatVersion: 1.0.0 + UseCaseFormatVersion: 1.1.0 Datasets: - sample: VehicleId: "7" # データセット毎にVehicleIdを指定する diff --git a/sample/traffic_light/scenario.yaml b/sample/traffic_light/scenario.yaml index c80cae71..15127ce8 100644 --- a/sample/traffic_light/scenario.yaml +++ b/sample/traffic_light/scenario.yaml @@ -5,7 +5,7 @@ SensorModel: aip_xx1 VehicleModel: jpntaxi Evaluation: UseCaseName: traffic_light - UseCaseFormatVersion: 1.0.0 + UseCaseFormatVersion: 1.1.0 Datasets: - sample: VehicleId: "7" # Specify VehicleId for each data set.