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.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: