From f0967a6763081faa93322d6a26154d986a5806fb Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 9 May 2023 17:04:32 +0900 Subject: [PATCH 01/27] feat: add support of regulatory element Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 10 ++++++++++ perception_eval/test/perception_lsim2d.py | 5 +---- 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 18bce33b..5c5cdc44 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -458,6 +458,8 @@ def _sample_to_frame_2d( frame_id_mapping: Dict[str, FrameID] = {} for frame_id_ in frame_ids: camera_type: str = frame_id_.value.upper() + if nusc_sample["data"].get(camera_type) is None: + continue sample_data_token = nusc_sample["data"][camera_type] sample_data_tokens.append(sample_data_token) frame_id_mapping[sample_data_token] = frame_id_ @@ -493,6 +495,13 @@ def _sample_to_frame_2d( semantic_label: LabelType = label_converter.convert_label(category_info["name"], attributes) if label_converter.label_type == TrafficLightLabel: + # NOTE: Check whether Regulatory Element is used + # in scene.json => description: "TLR, regulatory_element" + scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])[ + "description" + ].split(", ") + use_regulatory_element: bool = "regulatory_element" in scene_descriptions + for instance_record in nusc.instance: if instance_record["token"] == ann["instance_token"]: instance_name: str = instance_record["instance_name"] @@ -512,6 +521,7 @@ def _sample_to_frame_2d( visibility=visibility, ) objects_.append(object_) + print(len(objects_)) frame = dataset.FrameGroundTruth( unix_time=unix_time, diff --git a/perception_eval/test/perception_lsim2d.py b/perception_eval/test/perception_lsim2d.py index 1bfe0a92..dc365bb0 100644 --- a/perception_eval/test/perception_lsim2d.py +++ b/perception_eval/test/perception_lsim2d.py @@ -295,10 +295,7 @@ def visualize(self, frame_result: PerceptionFrameResult): ) for ground_truth_frame in classification_lsim.evaluator.ground_truth_frames: - objects_with_difference = get_objects_with_difference2d(ground_truth_frame.objects, label_to_unknown_rate=0.5) - # To avoid case of there is no object - if len(objects_with_difference) > 0: - objects_with_difference.pop(0) + objects_with_difference = ground_truth_frame.objects classification_lsim.callback( ground_truth_frame.unix_time, objects_with_difference, From 80513d03b8f0d7a9b33835f1f9bc86869d251e33 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 16 May 2023 17:57:33 +0900 Subject: [PATCH 02/27] feat: add new frame id named TrafficLight Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 34 ++++++++++++------- .../evaluation/result/object_result.py | 3 +- 2 files changed, 24 insertions(+), 13 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 5c5cdc44..831ed868 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -40,6 +40,7 @@ from perception_eval.common.shape import ShapeType from PIL import Image from pyquaternion.quaternion import Quaternion +import logging from . import dataset @@ -455,14 +456,26 @@ def _sample_to_frame_2d( unix_time: int = sample["timestamp"] sample_data_tokens: List[str] = [] - frame_id_mapping: Dict[str, FrameID] = {} + frame_id_mapping: Dict[str, FrameID] = {} for frame_id_ in frame_ids: - camera_type: str = frame_id_.value.upper() - if nusc_sample["data"].get(camera_type) is None: - continue - sample_data_token = nusc_sample["data"][camera_type] - sample_data_tokens.append(sample_data_token) - frame_id_mapping[sample_data_token] = frame_id_ + # TODO update + scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])[ + "description" + ].split(", ") + if "regulatory_element" in scene_descriptions: + for camera_type in (FrameID.CAM_TRAFFIC_LIGHT_FAR.value.upper(), FrameID.CAM_TRAFFIC_LIGHT_NEAR.value.upper()): + if nusc_sample["data"].get(camera_type) is None: + continue + sample_data_token = nusc_sample["data"][camera_type] + sample_data_tokens.append(sample_data_token) + frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT # frame_id_ + else: + camera_type: str = frame_id_.value.upper() + if nusc_sample["data"].get(camera_type) is None: + continue + sample_data_token = nusc_sample["data"][camera_type] + sample_data_tokens.append(sample_data_token) + frame_id_mapping[sample_data_token] = frame_id_ raw_data: Optional[Dict[str, np.ndarray]] = {} if load_raw_data else None if load_raw_data: @@ -497,10 +510,6 @@ def _sample_to_frame_2d( if label_converter.label_type == TrafficLightLabel: # NOTE: Check whether Regulatory Element is used # in scene.json => description: "TLR, regulatory_element" - scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])[ - "description" - ].split(", ") - use_regulatory_element: bool = "regulatory_element" in scene_descriptions for instance_record in nusc.instance: if instance_record["token"] == ann["instance_token"]: @@ -511,6 +520,8 @@ def _sample_to_frame_2d( visibility = None + logging.info(f"uuid: {uuid}") + object_: DynamicObject2D = DynamicObject2D( unix_time=unix_time, frame_id=frame_id_mapping[ann["sample_data_token"]], @@ -521,7 +532,6 @@ def _sample_to_frame_2d( visibility=visibility, ) objects_.append(object_) - print(len(objects_)) frame = dataset.FrameGroundTruth( unix_time=unix_time, diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 4c86fb71..f0393620 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -27,6 +27,7 @@ from perception_eval.common import ObjectType from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.common.label import LabelType +from perception_eval.common.schema import FrameID from perception_eval.common.status import MatchingStatus from perception_eval.common.threshold import get_label_threshold from perception_eval.evaluation.matching import CenterDistanceMatching @@ -390,7 +391,7 @@ def _get_object_results_with_id( ground_truth_objects_.remove(gt_object) # when there are rest of estimated objects, they all are FP. - if len(estimated_objects_) > 0: + if len(estimated_objects_) > 0 and not any([est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_]): object_results += _get_fp_object_results(estimated_objects_) return object_results From ea8b124b37ea675fe9ed5fa02f027445f252261f Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 27 Jun 2023 10:16:15 +0900 Subject: [PATCH 03/27] feat: update label Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 17 +++--- .../perception_eval/common/label.py | 60 ++++++++++++++----- 2 files changed, 54 insertions(+), 23 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 831ed868..ad5eb5d0 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -14,6 +14,7 @@ from __future__ import annotations +import logging from typing import Any from typing import Dict from typing import List @@ -40,7 +41,6 @@ from perception_eval.common.shape import ShapeType from PIL import Image from pyquaternion.quaternion import Quaternion -import logging from . import dataset @@ -456,19 +456,22 @@ def _sample_to_frame_2d( unix_time: int = sample["timestamp"] sample_data_tokens: List[str] = [] - frame_id_mapping: Dict[str, FrameID] = {} + frame_id_mapping: Dict[str, FrameID] = {} for frame_id_ in frame_ids: # TODO update scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])[ - "description" - ].split(", ") + "description" + ].split(", ") if "regulatory_element" in scene_descriptions: - for camera_type in (FrameID.CAM_TRAFFIC_LIGHT_FAR.value.upper(), FrameID.CAM_TRAFFIC_LIGHT_NEAR.value.upper()): + for camera_type in ( + FrameID.CAM_TRAFFIC_LIGHT_FAR.value.upper(), + FrameID.CAM_TRAFFIC_LIGHT_NEAR.value.upper(), + ): if nusc_sample["data"].get(camera_type) is None: continue sample_data_token = nusc_sample["data"][camera_type] sample_data_tokens.append(sample_data_token) - frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT # frame_id_ + frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT # frame_id_ else: camera_type: str = frame_id_.value.upper() if nusc_sample["data"].get(camera_type) is None: @@ -520,7 +523,7 @@ def _sample_to_frame_2d( visibility = None - logging.info(f"uuid: {uuid}") + logging.debug(f"uuid: {uuid}") object_: DynamicObject2D = DynamicObject2D( unix_time=unix_time, diff --git a/perception_eval/perception_eval/common/label.py b/perception_eval/perception_eval/common/label.py index cc42c942..b504f739 100644 --- a/perception_eval/perception_eval/common/label.py +++ b/perception_eval/perception_eval/common/label.py @@ -53,16 +53,25 @@ class TrafficLightLabel(Enum): # classification GREEN = "green" - RED = "red" + GREEN_STRAIGHT = "green_straight" + GREEN_LEFT = "green_left" + GREEN_RIGHT = "green_right" YELLOW = "yellow" + YELLOW_STRAIGHT = "yellow_straight" + YELLOW_LEFT = "yellow_left" + YELLOW_RIGHT = "yellow_right" + YELLOW_STRAIGHT_LEFT = "yellow_straight_left" + YELLOW_STRAIGHT_RIGHT = "yellow_straight_right" + YELLOW_STRAIGHT_LEFT_RIGHT = "yellow_straight_left_right" + RED = "red" RED_STRAIGHT = "red_straight" RED_LEFT = "red_left" - RED_LEFT_STRAIGHT = "red_left_straight" - RED_LEFT_DIAGONAL = "red_left_diagonal" RED_RIGHT = "red_right" - RED_RIGHT_STRAIGHT = "red_right_straight" + RED_STRAIGHT_LEFT = "red_straight_left" + RED_STRAIGHT_RIGHT = "red_straight_right" + RED_STRAIGHT_LEFT_RIGHT = "red_straight_left_right" + RED_LEFT_DIAGONAL = "red_left_diagonal" RED_RIGHT_DIAGONAL = "red_right_diagonal" - YELLOW_RIGHT = "yellow_right" # unknown is used in both detection and classification UNKNOWN = "unknown" @@ -341,33 +350,52 @@ def _get_traffic_light_paris( if evaluation_task == EvaluationTask.CLASSIFICATION2D: pair_list: List[Tuple[TrafficLightLabel, str]] = [ (TrafficLightLabel.GREEN, "green"), - (TrafficLightLabel.RED, "red"), + (TrafficLightLabel.GREEN_STRAIGHT, "green_straight"), + (TrafficLightLabel.GREEN_LEFT, "green_left"), + (TrafficLightLabel.GREEN_RIGHT, "green_right"), (TrafficLightLabel.YELLOW, "yellow"), + (TrafficLightLabel.YELLOW_STRAIGHT, "yellow_straight"), + (TrafficLightLabel.YELLOW_LEFT, "yellow_left"), + (TrafficLightLabel.YELLOW_RIGHT, "yellow_right"), + (TrafficLightLabel.YELLOW_STRAIGHT_LEFT, "yellow_straight_left"), + (TrafficLightLabel.YELLOW_STRAIGHT_LEFT_RIGHT, "yellow_straight_right"), + (TrafficLightLabel.RED, "red"), (TrafficLightLabel.RED_STRAIGHT, "red_straight"), (TrafficLightLabel.RED_LEFT, "red_left"), - (TrafficLightLabel.RED_LEFT_STRAIGHT, "red_left_straight"), - (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), (TrafficLightLabel.RED_RIGHT, "red_right"), - (TrafficLightLabel.RED_RIGHT_STRAIGHT, "red_right_straight"), + (TrafficLightLabel.RED_STRAIGHT_LEFT, "red_straight_left"), + (TrafficLightLabel.RED_STRAIGHT_RIGHT, "red_straight_right"), + (TrafficLightLabel.RED_STRAIGHT_LEFT_RIGHT, "red_straight_left_right"), (TrafficLightLabel.RED_RIGHT_DIAGONAL, "red_right_diagonal"), - (TrafficLightLabel.YELLOW_RIGHT, "yellow_right"), + (TrafficLightLabel.RED_RIGHT_DIAGONAL, "red_rightdiagonal"), + (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), + (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_leftdiagonal"), (TrafficLightLabel.UNKNOWN, "unknown"), (TrafficLightLabel.FP, "false_positive"), ] else: pair_list: List[Tuple[TrafficLightLabel, str]] = [ - (TrafficLightLabel.TRAFFIC_LIGHT, "traffic_light"), (TrafficLightLabel.TRAFFIC_LIGHT, "green"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red"), + (TrafficLightLabel.TRAFFIC_LIGHT, "green_straight"), + (TrafficLightLabel.TRAFFIC_LIGHT, "green_left"), + (TrafficLightLabel.TRAFFIC_LIGHT, "green_right"), (TrafficLightLabel.TRAFFIC_LIGHT, "yellow"), + (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_straight"), + (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_left"), + (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_right"), + (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_straight_left"), + (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_straight_right"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_left"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_straight"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_diagonal"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_right"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red_right_straight"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight_left"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight_right"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight_left_right"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_right_diagonal"), - (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_right"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_rightdiagonal"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_diagonal"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_leftdiagonal"), (TrafficLightLabel.UNKNOWN, "unknown"), (TrafficLightLabel.FP, "false_positive"), ] From 92472f93bf073bf9b1687b49c9f6b1e054926dd7 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 28 Jun 2023 19:50:19 +0900 Subject: [PATCH 04/27] feat: update to get object results without ID and stock fails Signed-off-by: ktro2828 --- .../perception_eval/common/dataset.py | 2 + .../evaluation/result/object_result.py | 48 ++++++++++++++++++- show_fail_data.py | 47 ++++++++++++++++++ 3 files changed, 96 insertions(+), 1 deletion(-) create mode 100644 show_fail_data.py diff --git a/perception_eval/perception_eval/common/dataset.py b/perception_eval/perception_eval/common/dataset.py index 2f0d4f82..c4b0c486 100644 --- a/perception_eval/perception_eval/common/dataset.py +++ b/perception_eval/perception_eval/common/dataset.py @@ -280,6 +280,8 @@ def get_now_frame( if diff_time < min_time: ground_truth_now_frame = ground_truth_frame min_time = diff_time + # if 0 < len(ground_truth_frame.objects) and (any([obj.uuid in ("10321", "179948") for obj in ground_truth_frame.objects]) and diff_time < threshold_min_time or ground_truth_frame.objects[0].uuid == "10321"): + # logging.info(f"uuids: {[obj.uuid for obj in ground_truth_frame.objects]}, diff time: {diff_time / 1000}") if min_time > threshold_min_time: logging.info( f"Now frame is {ground_truth_now_frame.unix_time} and time difference \ diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index f0393620..31eef0ad 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -14,6 +14,7 @@ from __future__ import annotations +import logging from typing import Callable from typing import List from typing import Optional @@ -27,6 +28,7 @@ from perception_eval.common import ObjectType from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.common.label import LabelType +from perception_eval.common.label import TrafficLightLabel from perception_eval.common.schema import FrameID from perception_eval.common.status import MatchingStatus from perception_eval.common.threshold import get_label_threshold @@ -304,7 +306,15 @@ def get_object_results( ground_truth_objects[0], type(estimated_objects[0]) ), f"Type of estimation and ground truth must be same, but got {type(estimated_objects[0])} and {type(ground_truth_objects[0])}" - if evaluation_task == EvaluationTask.CLASSIFICATION2D: + if ( + isinstance(estimated_objects[0], DynamicObject2D) + and (estimated_objects[0].roi is None or ground_truth_objects[0].roi is None) + and isinstance(estimated_objects[0].semantic_label.label, TrafficLightLabel) + ): + return _get_object_results_for_tlr(estimated_objects, ground_truth_objects) + elif isinstance(estimated_objects[0], DynamicObject2D) and ( + estimated_objects[0].roi is None or ground_truth_objects[0].roi is None + ): return _get_object_results_with_id(estimated_objects, ground_truth_objects) matching_method_module, maximize = _get_matching_module(matching_mode) @@ -397,6 +407,42 @@ def _get_object_results_with_id( return object_results +def _get_object_results_for_tlr( + estimated_objects: List[DynamicObject2D], + ground_truth_objects: List[DynamicObject2D], +) -> List[DynamicObjectWithPerceptionResult]: + """Returns the list of DynamicObjectWithPerceptionResult for TLR classification. + + This function is used in 2D classification evaluation. + + Args: + estimated_objects (List[DynamicObject2D]): Estimated objects list. + ground_truth_objects (List[DynamicObject2D]): Ground truth objects list. + + Returns: + object_results (List[DynamicObjectWithPerceptionEvaluation]): Object results list. + """ + object_results: List[DynamicObjectWithPerceptionResult] = [] + estimated_objects_ = estimated_objects.copy() + ground_truth_objects_ = ground_truth_objects.copy() + for est_object in estimated_objects: + for gt_object in ground_truth_objects_: + if est_object.semantic_label == gt_object.semantic_label: + object_results.append( + DynamicObjectWithPerceptionResult( + estimated_object=est_object, + ground_truth_object=gt_object, + ) + ) + estimated_objects_.remove(est_object) + ground_truth_objects_.remove(gt_object) + logging.info(f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}") + # when there are rest of a GT objects, one of the estimated objects is FP. + if 0 < len(ground_truth_objects_): + object_results += _get_fp_object_results([estimated_objects_[0]]) + return object_results + + def _get_fp_object_results( estimated_objects: List[ObjectType], ) -> List[DynamicObjectWithPerceptionResult]: diff --git a/show_fail_data.py b/show_fail_data.py new file mode 100644 index 00000000..cf0ab585 --- /dev/null +++ b/show_fail_data.py @@ -0,0 +1,47 @@ +import argparse +import json +import cv2 +import os.path as osp + +def main(): + parser = argparse.ArgumentParser() + parser.add_argument("fail_info", type=str, help="path of fail_info.json") + parser.add_argument("data", type=str, help="root path of dataset") + args = parser.parse_args() + + with open(args.fail_info, "r") as f: + fail_records = json.load(f) + + with open(osp.join(args.data, "annotation/sample_data.json"), "r") as f: + sample_data_records = json.load(f) + + print(f"Num Fail: {len(fail_records)}") + + for fail_info in fail_records: + timestamp = fail_info["timestamp"] + sample_data = None + for sd_record in sample_data_records: + if sd_record["timestamp"] == timestamp: + sample_data = sd_record + if sample_data is None: + print(f"[WARN]: There is no corresponding sample data!!, timestamp: {timestamp}") + continue + filename = sample_data["filename"] + img = cv2.imread(osp.join(args.data, filename)) + for fp_result in fail_info.get("fp", []): + img = cv2.putText(img, text=f"[FP-Est]: {fp_result['est']}", org=(30, 30), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(255, 255, 255)) + img = cv2.putText(img, text=f"[FP-GT]: {fp_result['gt']}", org=(50, 50), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(0, 0, 255)) + + for fn_result in fail_info.get("fn", []): + img = cv2.putText(img, text=f"[FN-GT]: {fn_result['gt']}", org=(100, 100), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(0, 0, 255)) + + cv2.imshow("img", img) + key =cv2.waitKey(0) + cv2.destroyAllWindows() + + if key == 27: + break + + +if __name__ == "__main__": + main() From 39125a80a8dbe17519e6f533e5eaffd6d952cf28 Mon Sep 17 00:00:00 2001 From: Shunsuke Miura Date: Mon, 31 Jul 2023 19:04:37 +0900 Subject: [PATCH 05/27] add map loader for traffic light regualtory element Signed-off-by: Shunsuke Miura --- simple_lanelet_loader/CMakeLists.txt | 10 ++ simple_lanelet_loader/package.xml | 18 +++ .../simple_lanelet_loader/__init__.py | 0 .../traffic_light_loader.py | 106 ++++++++++++++++++ simple_lanelet_loader/test_map_load.py | 39 +++++++ 5 files changed, 173 insertions(+) create mode 100644 simple_lanelet_loader/CMakeLists.txt create mode 100644 simple_lanelet_loader/package.xml create mode 100644 simple_lanelet_loader/simple_lanelet_loader/__init__.py create mode 100644 simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py create mode 100644 simple_lanelet_loader/test_map_load.py diff --git a/simple_lanelet_loader/CMakeLists.txt b/simple_lanelet_loader/CMakeLists.txt new file mode 100644 index 00000000..a0b0d868 --- /dev/null +++ b/simple_lanelet_loader/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.5) +project(simple_lanelet_loader) + +find_package(ament_cmake_auto REQUIRED) +find_package(ament_cmake_python REQUIRED) +ament_auto_find_build_dependencies() + +ament_python_install_package(${PROJECT_NAME}) + +ament_auto_package() diff --git a/simple_lanelet_loader/package.xml b/simple_lanelet_loader/package.xml new file mode 100644 index 00000000..58068f22 --- /dev/null +++ b/simple_lanelet_loader/package.xml @@ -0,0 +1,18 @@ + + + + simple_lanelet_loader + 1.0.7 + simple lanelet loader for logsim + Shunsuke Miura + Apache V2 + + ament_copyright + ament_flake8 + ament_pep257 + python3-pytest + + + ament_cmake + + diff --git a/simple_lanelet_loader/simple_lanelet_loader/__init__.py b/simple_lanelet_loader/simple_lanelet_loader/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py b/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py new file mode 100644 index 00000000..328dae55 --- /dev/null +++ b/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py @@ -0,0 +1,106 @@ +import logging +from typing import Dict +from typing import List +from typing import Optional +import xml.etree.ElementTree as ET + +import numpy as np + + +class TrafficLightLoader: + def __init__(self, map_path) -> None: + tree = ET.parse(map_path) + root = tree.getroot() + + # 1. extract node, way relation from xml + self.nodes = {} + self.traffic_light_ways = {} + self.traffic_light_regulatory_elements = {} + + for child in root: + if child.tag == "node": + ref_id, x, y, z = extract_node(child) + self.nodes[ref_id] = [x, y, z] + elif child.tag == "way": + traffic_light_way = extract_traffic_light_way(child) + if traffic_light_way: + self.traffic_light_ways |= traffic_light_way + elif child.tag == "relation": + ids = int(child.attrib["id"]) + element = extract_traffic_light_regulatory_element(child) + if element: + self.traffic_light_regulatory_elements |= element + + self.traffic_light_positions = {} + for id, refs in self.traffic_light_ways.items(): + traffic_light_position = np.array([0.0, 0.0, 0.0]) + for ref_id in refs: + traffic_light_position += np.array(self.nodes[ref_id]) + self.traffic_light_positions[id] = traffic_light_position / 2 + + def get_distance_to_traffic_light_group(self, regulatory_element_id, origin): + distance = 10000 + origin = np.array(origin) + logging.info(f"regulatory_element_id: {regulatory_element_id}") + for id, refers in self.traffic_light_regulatory_elements.items(): + if id == regulatory_element_id: + logging.info(f"id:{id}, refers:{refers}") + for ref_id in refers: + if not ref_id in self.traffic_light_positions.keys(): + continue + try: + traffic_light_position = self.traffic_light_positions[ref_id] + # logging.info(f"traffic_light_position: {traffic_light_position}, {traffic_light_position-origin}") + dist = np.linalg.norm(traffic_light_position - origin) + # logging.info(f"distance={dist}") + if dist < distance: + distance = dist + except KeyError: + logging.info(f"KeyError: @{regulatory_element_id}") + + return distance + + +""" utils for maploader program""" + + +def extract_node(child): + x, y, z = 0, 0, 0 + for tag in child: + if tag.attrib['k'] == 'local_x': + x = tag.attrib['v'] + elif tag.attrib['k'] == 'local_y': + y = tag.attrib['v'] + elif tag.attrib['k'] == 'ele': + z = tag.attrib['v'] + return child.attrib["id"], float(x), float(y), float(z) + + +def extract_traffic_light_way(child): + refs = [] + tags = {} + for tag in child: + if tag.tag == "nd": + refs.append(tag.attrib["ref"]) + # elif tag.attrib["k"] == "type": + # if tag.attrib["v"] == "traffic_light": + elif tag.attrib["k"] == "subtype": + if tag.attrib["v"] == "red_yellow_green": + return {child.attrib["id"]: refs} + + +def extract_traffic_light_regulatory_element(child) -> Optional[Dict[str, List[int]]]: + refers = [] + for tag in child: + if tag.tag == "member": + if tag.attrib["role"] == "refers": + refers.append(tag.attrib["ref"]) + if tag.tag == "tag": + if tag.attrib["k"] == "type" and tag.attrib["v"] == "regulatory_element": + continue + elif tag.attrib["k"] == "subtype" and tag.attrib["v"] == "traffic_light": + continue + else: + return + regulatory_element = {child.attrib["id"]: refers} + return regulatory_element diff --git a/simple_lanelet_loader/test_map_load.py b/simple_lanelet_loader/test_map_load.py new file mode 100644 index 00000000..24c3bc43 --- /dev/null +++ b/simple_lanelet_loader/test_map_load.py @@ -0,0 +1,39 @@ +import os + +import numpy as np + +from simple_lanelet_loader.traffic_light_loader import TrafficLightLoader + +default_map_path = "~/lanelet2_map.osm" + + +def refine_path(path): + # fix ~ + path = os.path.expanduser(path) + # fix $HOME + path = os.path.expandvars(path) + return path + + +def main(map_path: str): + # load map obj + map_obj = TrafficLightLoader(map_path) + print( + map_obj.get_distance_to_traffic_light_group( + "179563", np.array([89434.6492, 42630.8311, 5.686]) + ) + ) + + print(map_obj) + + +if __name__ == "__main__": + import argparse + + parser = argparse.ArgumentParser() + parser.add_argument("--map_path", type=str, default=default_map_path) + + # get args + args = parser.parse_args() + map_path = refine_path(args.map_path) + main(map_path) From c299780377ec4b3d811a41dc9499bc250f5852d6 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Mon, 31 Jul 2023 19:21:16 +0900 Subject: [PATCH 06/27] fix: resolve label name in test Signed-off-by: ktro2828 --- perception_eval/test/common/test_label.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/perception_eval/test/common/test_label.py b/perception_eval/test/common/test_label.py index 39ab0003..3ea259b1 100644 --- a/perception_eval/test/common/test_label.py +++ b/perception_eval/test/common/test_label.py @@ -65,10 +65,10 @@ (TrafficLightLabel.YELLOW, "yellow"), (TrafficLightLabel.RED_STRAIGHT, "red_straight"), (TrafficLightLabel.RED_LEFT, "red_left"), - (TrafficLightLabel.RED_LEFT_STRAIGHT, "red_left_straight"), + (TrafficLightLabel.RED_STRAIGHT_LEFT, "red_left_straight"), (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), (TrafficLightLabel.RED_RIGHT, "red_right"), - (TrafficLightLabel.RED_RIGHT_STRAIGHT, "red_right_straight"), + (TrafficLightLabel.RED_STRAIGHT_RIGHT, "red_right_straight"), (TrafficLightLabel.RED_RIGHT_DIAGONAL, "red_right_diagonal"), (TrafficLightLabel.YELLOW_RIGHT, "yellow_right"), (TrafficLightLabel.UNKNOWN, "unknown"), @@ -81,10 +81,10 @@ (TrafficLightLabel.TRAFFIC_LIGHT, "yellow"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_left"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_straight"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight_left"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_diagonal"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_right"), - (TrafficLightLabel.TRAFFIC_LIGHT, "red_right_straight"), + (TrafficLightLabel.TRAFFIC_LIGHT, "red_straight_right"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_right_diagonal"), (TrafficLightLabel.TRAFFIC_LIGHT, "yellow_right"), (TrafficLightLabel.UNKNOWN, "unknown"), From f8782e088ac61eabb4d182047f22494665488d45 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Mon, 31 Jul 2023 21:02:00 +0900 Subject: [PATCH 07/27] style: fix pre-commit Signed-off-by: ktro2828 --- .../evaluation/result/object_result.py | 8 +++-- show_fail_data.py | 33 ++++++++++++++++--- 2 files changed, 34 insertions(+), 7 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 31eef0ad..364d32cc 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -401,7 +401,9 @@ def _get_object_results_with_id( ground_truth_objects_.remove(gt_object) # when there are rest of estimated objects, they all are FP. - if len(estimated_objects_) > 0 and not any([est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_]): + if len(estimated_objects_) > 0 and not any( + [est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_] + ): object_results += _get_fp_object_results(estimated_objects_) return object_results @@ -436,7 +438,9 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) - logging.info(f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}") + logging.info( + f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}" + ) # when there are rest of a GT objects, one of the estimated objects is FP. if 0 < len(ground_truth_objects_): object_results += _get_fp_object_results([estimated_objects_[0]]) diff --git a/show_fail_data.py b/show_fail_data.py index cf0ab585..5afcfecc 100644 --- a/show_fail_data.py +++ b/show_fail_data.py @@ -1,8 +1,10 @@ import argparse import json -import cv2 import os.path as osp +import cv2 + + def main(): parser = argparse.ArgumentParser() parser.add_argument("fail_info", type=str, help="path of fail_info.json") @@ -29,14 +31,35 @@ def main(): filename = sample_data["filename"] img = cv2.imread(osp.join(args.data, filename)) for fp_result in fail_info.get("fp", []): - img = cv2.putText(img, text=f"[FP-Est]: {fp_result['est']}", org=(30, 30), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(255, 255, 255)) - img = cv2.putText(img, text=f"[FP-GT]: {fp_result['gt']}", org=(50, 50), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(0, 0, 255)) + img = cv2.putText( + img, + text=f"[FP-Est]: {fp_result['est']}", + org=(30, 30), + fontFace=cv2.FONT_HERSHEY_SIMPLEX, + fontScale=1.0, + color=(255, 255, 255), + ) + img = cv2.putText( + img, + text=f"[FP-GT]: {fp_result['gt']}", + org=(50, 50), + fontFace=cv2.FONT_HERSHEY_SIMPLEX, + fontScale=1.0, + color=(0, 0, 255), + ) for fn_result in fail_info.get("fn", []): - img = cv2.putText(img, text=f"[FN-GT]: {fn_result['gt']}", org=(100, 100), fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1.0, color=(0, 0, 255)) + img = cv2.putText( + img, + text=f"[FN-GT]: {fn_result['gt']}", + org=(100, 100), + fontFace=cv2.FONT_HERSHEY_SIMPLEX, + fontScale=1.0, + color=(0, 0, 255), + ) cv2.imshow("img", img) - key =cv2.waitKey(0) + key = cv2.waitKey(0) cv2.destroyAllWindows() if key == 27: From a759eb04d2574efa9421c12458b0664f05943a47 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Mon, 31 Jul 2023 21:05:10 +0900 Subject: [PATCH 08/27] chore: fix spell check Signed-off-by: ktro2828 --- .../perception_eval/common/label.py | 2 ++ .../traffic_light_loader.py | 22 +++++++++---------- 2 files changed, 13 insertions(+), 11 deletions(-) diff --git a/perception_eval/perception_eval/common/label.py b/perception_eval/perception_eval/common/label.py index b504f739..ca52fb5d 100644 --- a/perception_eval/perception_eval/common/label.py +++ b/perception_eval/perception_eval/common/label.py @@ -12,6 +12,8 @@ # See the License for the specific language governing permissions and # limitations under the License. +# cspell: ignore leftdiagonal, rightdiagonal + from __future__ import annotations from dataclasses import dataclass diff --git a/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py b/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py index 328dae55..70c2b207 100644 --- a/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py +++ b/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py @@ -2,7 +2,7 @@ from typing import Dict from typing import List from typing import Optional -import xml.etree.ElementTree as ET +import xml.etree.ElementTree as ET # noqa import numpy as np @@ -26,7 +26,7 @@ def __init__(self, map_path) -> None: if traffic_light_way: self.traffic_light_ways |= traffic_light_way elif child.tag == "relation": - ids = int(child.attrib["id"]) + # ids = int(child.attrib["id"]) element = extract_traffic_light_regulatory_element(child) if element: self.traffic_light_regulatory_elements |= element @@ -46,7 +46,7 @@ def get_distance_to_traffic_light_group(self, regulatory_element_id, origin): if id == regulatory_element_id: logging.info(f"id:{id}, refers:{refers}") for ref_id in refers: - if not ref_id in self.traffic_light_positions.keys(): + if ref_id not in self.traffic_light_positions.keys(): continue try: traffic_light_position = self.traffic_light_positions[ref_id] @@ -61,24 +61,24 @@ def get_distance_to_traffic_light_group(self, regulatory_element_id, origin): return distance -""" utils for maploader program""" +""" utils for map-loader program""" def extract_node(child): x, y, z = 0, 0, 0 for tag in child: - if tag.attrib['k'] == 'local_x': - x = tag.attrib['v'] - elif tag.attrib['k'] == 'local_y': - y = tag.attrib['v'] - elif tag.attrib['k'] == 'ele': - z = tag.attrib['v'] + if tag.attrib["k"] == "local_x": + x = tag.attrib["v"] + elif tag.attrib["k"] == "local_y": + y = tag.attrib["v"] + elif tag.attrib["k"] == "ele": + z = tag.attrib["v"] return child.attrib["id"], float(x), float(y), float(z) def extract_traffic_light_way(child): refs = [] - tags = {} + # tags = {} for tag in child: if tag.tag == "nd": refs.append(tag.attrib["ref"]) From 0f86e1ce26a58b0c06daabfb13e50c85ac0d5222 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 31 Oct 2023 23:38:45 +0000 Subject: [PATCH 09/27] style(pre-commit): autofix --- perception_eval/perception_eval/common/dataset_utils.py | 4 +--- .../perception_eval/evaluation/result/object_result.py | 8 ++------ simple_lanelet_loader/test_map_load.py | 6 +----- 3 files changed, 4 insertions(+), 14 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index ad5eb5d0..74bb86e0 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -459,9 +459,7 @@ def _sample_to_frame_2d( frame_id_mapping: Dict[str, FrameID] = {} for frame_id_ in frame_ids: # TODO update - scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])[ - "description" - ].split(", ") + scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])["description"].split(", ") if "regulatory_element" in scene_descriptions: for camera_type in ( FrameID.CAM_TRAFFIC_LIGHT_FAR.value.upper(), diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 364d32cc..31eef0ad 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -401,9 +401,7 @@ def _get_object_results_with_id( ground_truth_objects_.remove(gt_object) # when there are rest of estimated objects, they all are FP. - if len(estimated_objects_) > 0 and not any( - [est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_] - ): + if len(estimated_objects_) > 0 and not any([est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_]): object_results += _get_fp_object_results(estimated_objects_) return object_results @@ -438,9 +436,7 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) - logging.info( - f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}" - ) + logging.info(f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}") # when there are rest of a GT objects, one of the estimated objects is FP. if 0 < len(ground_truth_objects_): object_results += _get_fp_object_results([estimated_objects_[0]]) diff --git a/simple_lanelet_loader/test_map_load.py b/simple_lanelet_loader/test_map_load.py index 24c3bc43..3c793414 100644 --- a/simple_lanelet_loader/test_map_load.py +++ b/simple_lanelet_loader/test_map_load.py @@ -18,11 +18,7 @@ def refine_path(path): def main(map_path: str): # load map obj map_obj = TrafficLightLoader(map_path) - print( - map_obj.get_distance_to_traffic_light_group( - "179563", np.array([89434.6492, 42630.8311, 5.686]) - ) - ) + print(map_obj.get_distance_to_traffic_light_group("179563", np.array([89434.6492, 42630.8311, 5.686]))) print(map_obj) From 4aa776019d2fc9a94ff5080f9149ee5e539df391 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 1 Nov 2023 11:03:02 +0900 Subject: [PATCH 10/27] fix: add `FrameID.TRAFFIC_LIGHT` Signed-off-by: ktro2828 --- perception_eval/perception_eval/common/dataset_utils.py | 2 +- perception_eval/perception_eval/common/schema.py | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 74bb86e0..eb02876f 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -469,7 +469,7 @@ def _sample_to_frame_2d( continue sample_data_token = nusc_sample["data"][camera_type] sample_data_tokens.append(sample_data_token) - frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT # frame_id_ + frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT else: camera_type: str = frame_id_.value.upper() if nusc_sample["data"].get(camera_type) is None: diff --git a/perception_eval/perception_eval/common/schema.py b/perception_eval/perception_eval/common/schema.py index d43c4fe6..2036f54e 100644 --- a/perception_eval/perception_eval/common/schema.py +++ b/perception_eval/perception_eval/common/schema.py @@ -37,6 +37,9 @@ class FrameID(Enum): CAM_TRAFFIC_LIGHT_NEAR = "cam_traffic_light_near" CAM_TRAFFIC_LIGHT_FAR = "cam_traffic_light_far" + # Integrated TLR camera frame + TRAFFIC_LIGHT = "traffic_light" + def __eq__(self, __o: object) -> bool: if isinstance(__o, str): return self.value == __o From b80c07181f7c9da38d9ab8d06a8104d2ef99ecad Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 13:50:28 +0900 Subject: [PATCH 11/27] fix: avoid to try remove objects have already been removed Signed-off-by: ktro2828 --- .../perception_eval/evaluation/result/object_result.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 31eef0ad..7e9ac308 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -425,6 +425,9 @@ def _get_object_results_for_tlr( object_results: List[DynamicObjectWithPerceptionResult] = [] estimated_objects_ = estimated_objects.copy() ground_truth_objects_ = ground_truth_objects.copy() + # TODO(ktro282): + # In case of there are multiple objects which have same regulatory element id, + # it might be matched with unintended GT for est_object in estimated_objects: for gt_object in ground_truth_objects_: if est_object.semantic_label == gt_object.semantic_label: @@ -437,6 +440,7 @@ def _get_object_results_for_tlr( estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) logging.info(f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}") + continue # when there are rest of a GT objects, one of the estimated objects is FP. if 0 < len(ground_truth_objects_): object_results += _get_fp_object_results([estimated_objects_[0]]) From d54a1ba933d98a7e1cbf3ffd225dbef76c4739db Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 16:33:43 +0900 Subject: [PATCH 12/27] feat: add support of labels for crosswalk traffic light Signed-off-by: ktro2828 --- perception_eval/perception_eval/common/label.py | 12 ++++++++++++ perception_eval/test/perception_lsim2d.py | 16 +++++++++++++--- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/perception_eval/perception_eval/common/label.py b/perception_eval/perception_eval/common/label.py index ca52fb5d..c2b732c0 100644 --- a/perception_eval/perception_eval/common/label.py +++ b/perception_eval/perception_eval/common/label.py @@ -54,6 +54,7 @@ class TrafficLightLabel(Enum): TRAFFIC_LIGHT = "traffic_light" # classification + # === for vehicle === GREEN = "green" GREEN_STRAIGHT = "green_straight" GREEN_LEFT = "green_left" @@ -75,6 +76,11 @@ class TrafficLightLabel(Enum): RED_LEFT_DIAGONAL = "red_left_diagonal" RED_RIGHT_DIAGONAL = "red_right_diagonal" + # === for crosswalk === + CROSSWALK_RED = "crosswalk_red" + CROSSWALK_GREEN = "crosswalk_green" + CROSSWALK_UNKNOWN = "crosswalk_unknown" + # unknown is used in both detection and classification UNKNOWN = "unknown" @@ -373,6 +379,9 @@ def _get_traffic_light_paris( (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_leftdiagonal"), (TrafficLightLabel.UNKNOWN, "unknown"), + (TrafficLightLabel.CROSSWALK_RED, "crosswalk_red"), + (TrafficLightLabel.CROSSWALK_GREEN, "crosswalk_green"), + (TrafficLightLabel.CROSSWALK_UNKNOWN, "crosswalk_unknown"), (TrafficLightLabel.FP, "false_positive"), ] else: @@ -398,7 +407,10 @@ def _get_traffic_light_paris( (TrafficLightLabel.TRAFFIC_LIGHT, "red_rightdiagonal"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_left_diagonal"), (TrafficLightLabel.TRAFFIC_LIGHT, "red_leftdiagonal"), + (TrafficLightLabel.TRAFFIC_LIGHT, "crosswalk_red"), + (TrafficLightLabel.TRAFFIC_LIGHT, "crosswalk_green"), (TrafficLightLabel.UNKNOWN, "unknown"), + (TrafficLightLabel.UNKNOWN, "crosswalk_unknown"), (TrafficLightLabel.FP, "false_positive"), ] return pair_list diff --git a/perception_eval/test/perception_lsim2d.py b/perception_eval/test/perception_lsim2d.py index dc365bb0..b18a54c6 100644 --- a/perception_eval/test/perception_lsim2d.py +++ b/perception_eval/test/perception_lsim2d.py @@ -59,7 +59,15 @@ def __init__( # If target_labels = None, all labels will be evaluated. evaluation_config_dict.update( dict( - target_labels=["green", "red", "yellow", "unknown"] + target_labels=[ + "green", + "red", + "yellow", + "unknown", + "crosswalk_green", + "crosswalk_red", + "crosswalk_unknown", + ] if label_prefix == "traffic_light" else ["car", "bicycle", "pedestrian", "motorbike"], ignore_attributes=["cycle_state.without_rider"] if label_prefix == "autoware" else None, @@ -106,12 +114,14 @@ def callback( # 1 frameの評価 target_labels = ( - ["green", "red", "yellow", "unknown"] + ["green", "red", "yellow", "unknown", "crosswalk_green", "crosswalk_red", "crosswalk_unknown"] if self.label_prefix == "traffic_light" else ["car", "bicycle", "pedestrian", "motorbike"] ) ignore_attributes = ["cycle_state.without_rider"] if self.label_prefix == "autoware" else None - matching_threshold_list = None if self.evaluation_task == "classification2d" else [0.5, 0.5, 0.5, 0.5] + matching_threshold_list = ( + None if self.evaluation_task == "classification2d" else [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5] + ) # 距離などでUC評価objectを選別するためのインターフェイス(PerceptionEvaluationManager初期化時にConfigを設定せず、関数受け渡しにすることで動的に変更可能なInterface) # どれを注目物体とするかのparam critical_object_filter_config: CriticalObjectFilterConfig = CriticalObjectFilterConfig( From d151f8136d495d98073d6bf7231c0e5f84415952 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 16:34:31 +0900 Subject: [PATCH 13/27] fix: update to assign same uuid Signed-off-by: ktro2828 --- .../evaluation/result/object_result.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 7e9ac308..0bb4f706 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -425,12 +425,9 @@ def _get_object_results_for_tlr( object_results: List[DynamicObjectWithPerceptionResult] = [] estimated_objects_ = estimated_objects.copy() ground_truth_objects_ = ground_truth_objects.copy() - # TODO(ktro282): - # In case of there are multiple objects which have same regulatory element id, - # it might be matched with unintended GT for est_object in estimated_objects: for gt_object in ground_truth_objects_: - if est_object.semantic_label == gt_object.semantic_label: + if est_object.uuid == gt_object.uuid and est_object.semantic_label == gt_object.semantic_label: object_results.append( DynamicObjectWithPerceptionResult( estimated_object=est_object, @@ -439,8 +436,10 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) - logging.info(f"[OK] Est: {est_object.semantic_label.label}, GT: {gt_object.semantic_label.label}") - continue + logging.info( + f"[OK] Est: {est_object.semantic_label.label}:{est_object.uuid}, " + f"GT: {gt_object.semantic_label.label}:{gt_object.uuid}" + ) # when there are rest of a GT objects, one of the estimated objects is FP. if 0 < len(ground_truth_objects_): object_results += _get_fp_object_results([estimated_objects_[0]]) From aa568e3ac5d74579de5f009ce77492d32b596fe8 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 16:34:52 +0900 Subject: [PATCH 14/27] fix: update to avoid error Signed-off-by: ktro2828 --- .../perception_eval/visualization/perception_visualizer2d.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/perception_eval/perception_eval/visualization/perception_visualizer2d.py b/perception_eval/perception_eval/visualization/perception_visualizer2d.py index 7785e7dd..9096572f 100644 --- a/perception_eval/perception_eval/visualization/perception_visualizer2d.py +++ b/perception_eval/perception_eval/visualization/perception_visualizer2d.py @@ -115,8 +115,8 @@ def init_figure(self) -> Tuple[Figure, np.ndarray]: self.label_type: Union[AutowareLabel, TrafficLightLabel] = self.__config.label_converter.label_type if self.label_type == TrafficLightLabel: - self.camera_names: Tuple[str] = ("cam_traffic_light_near", "cam_traffic_light_far") - fig, axes = plt.subplots(1, 2, figsize=self.__figsize, gridspec_kw=dict(wspace=0)) + self.camera_names: Tuple[str] = ("cam_traffic_light_near", "cam_traffic_light_far", "traffic_light") + fig, axes = plt.subplots(1, 3, figsize=self.__figsize, gridspec_kw=dict(wspace=0)) elif self.label_type == AutowareLabel: self.camera_names: Tuple[str] = ( "cam_front_left", From 6c02b726254cd94b16642e0439d9005518c80534 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 16:35:16 +0900 Subject: [PATCH 15/27] feat: update to merge multiple traffic lights with same uuid Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 63 +++++++++++++++++-- 1 file changed, 57 insertions(+), 6 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index eb02876f..2d2556c0 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -492,6 +492,8 @@ def _sample_to_frame_2d( ] objects_: List[DynamicObject2D] = [] + # used to merge multiple traffic lights with same regulatory element ID + uuids: List[str] = [] for ann in object_annotations: if evaluation_task in (EvaluationTask.DETECTION2D, EvaluationTask.TRACKING2D): bbox: List[float] = ann["bbox"] @@ -511,18 +513,15 @@ def _sample_to_frame_2d( if label_converter.label_type == TrafficLightLabel: # NOTE: Check whether Regulatory Element is used # in scene.json => description: "TLR, regulatory_element" - for instance_record in nusc.instance: if instance_record["token"] == ann["instance_token"]: instance_name: str = instance_record["instance_name"] uuid: str = instance_name.split(":")[-1] + break + uuids.append(uuid) else: uuid: str = ann["instance_token"] - visibility = None - - logging.debug(f"uuid: {uuid}") - object_: DynamicObject2D = DynamicObject2D( unix_time=unix_time, frame_id=frame_id_mapping[ann["sample_data_token"]], @@ -530,10 +529,13 @@ def _sample_to_frame_2d( semantic_label=semantic_label, roi=roi, uuid=uuid, - visibility=visibility, + visibility=None, ) objects_.append(object_) + if label_converter.label_type == TrafficLightLabel and evaluation_task == EvaluationTask.CLASSIFICATION2D: + objects_ = _merge_duplicated_traffic_lights(unix_time, objects_, uuids) + frame = dataset.FrameGroundTruth( unix_time=unix_time, frame_name=frame_name, @@ -542,3 +544,52 @@ def _sample_to_frame_2d( ) return frame + + +def _merge_duplicated_traffic_lights( + unix_time: int, + objects: List[DynamicObject2D], + uuids: List[str], +) -> List[DynamicObject2D]: + """Merge traffic light objects which have same uuid. + + Args: + unix_time (int): Current unix timestamp. + objects (List[DynamicObject2D]): List of traffic light objects. + It can contain the multiple traffic lights with same uuid. + uuids (List[str]): List of uuids. + + Returns: + List[DynamicObject2D]: List of merged results. + """ + uuids = set(uuids) + ret_objects: List[DynamicObject2D] = [] + for uuid in uuids: + candidates = [obj for obj in objects if obj.uuid == uuid] + candidate_labels = [obj.semantic_label for obj in candidates] + if all([label == candidate_labels[0] for label in candidate_labels]): + # all unknown or not unknown + semantic_label = candidate_labels[0] + else: + unique_labels = set([obj.semantic_label.label for obj in candidates]) + assert len(unique_labels) == 2, ( + "If the same regulatory element ID is assigned to multiple traffic lights, " + f"it must annotated with only two labels: (unknown, another one). But got, {unique_labels}" + ) + semantic_label = [ + label + for label in candidate_labels + if label.label != TrafficLightLabel.UNKNOWN and TrafficLightLabel.CROSSWALK_UNKNOWN + ][0] + merged_object = DynamicObject2D( + unix_time=unix_time, + frame_id=candidates[0].frame_id, + semantic_score=1.0, + semantic_label=semantic_label, + roi=None, + uuid=uuid, + visibility=None, + ) + ret_objects.append(merged_object) + assert len(ret_objects) == len(set([obj.uuid for obj in ret_objects])) + return ret_objects From b41e74395f029ed03bd39e7ffdd0063877ecca4a Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 21 Nov 2023 16:57:07 +0900 Subject: [PATCH 16/27] revert: remove label of traffic light for crossswalk Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 7 ++----- .../perception_eval/common/label.py | 11 +++------- perception_eval/test/perception_lsim2d.py | 21 ++++--------------- 3 files changed, 9 insertions(+), 30 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 2d2556c0..43000a37 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -576,11 +576,8 @@ def _merge_duplicated_traffic_lights( "If the same regulatory element ID is assigned to multiple traffic lights, " f"it must annotated with only two labels: (unknown, another one). But got, {unique_labels}" ) - semantic_label = [ - label - for label in candidate_labels - if label.label != TrafficLightLabel.UNKNOWN and TrafficLightLabel.CROSSWALK_UNKNOWN - ][0] + semantic_label = [label for label in candidate_labels if label.label != TrafficLightLabel.UNKNOWN][0] + assert semantic_label.label != TrafficLightLabel.UNKNOWN merged_object = DynamicObject2D( unix_time=unix_time, frame_id=candidates[0].frame_id, diff --git a/perception_eval/perception_eval/common/label.py b/perception_eval/perception_eval/common/label.py index c2b732c0..2bf27ff1 100644 --- a/perception_eval/perception_eval/common/label.py +++ b/perception_eval/perception_eval/common/label.py @@ -76,11 +76,6 @@ class TrafficLightLabel(Enum): RED_LEFT_DIAGONAL = "red_left_diagonal" RED_RIGHT_DIAGONAL = "red_right_diagonal" - # === for crosswalk === - CROSSWALK_RED = "crosswalk_red" - CROSSWALK_GREEN = "crosswalk_green" - CROSSWALK_UNKNOWN = "crosswalk_unknown" - # unknown is used in both detection and classification UNKNOWN = "unknown" @@ -379,9 +374,9 @@ def _get_traffic_light_paris( (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_leftdiagonal"), (TrafficLightLabel.UNKNOWN, "unknown"), - (TrafficLightLabel.CROSSWALK_RED, "crosswalk_red"), - (TrafficLightLabel.CROSSWALK_GREEN, "crosswalk_green"), - (TrafficLightLabel.CROSSWALK_UNKNOWN, "crosswalk_unknown"), + (TrafficLightLabel.RED, "crosswalk_red"), + (TrafficLightLabel.GREEN, "crosswalk_green"), + (TrafficLightLabel.UNKNOWN, "crosswalk_unknown"), (TrafficLightLabel.FP, "false_positive"), ] else: diff --git a/perception_eval/test/perception_lsim2d.py b/perception_eval/test/perception_lsim2d.py index b18a54c6..b274571e 100644 --- a/perception_eval/test/perception_lsim2d.py +++ b/perception_eval/test/perception_lsim2d.py @@ -45,10 +45,7 @@ def __init__( if evaluation_task in ("detection2d", "tracking2d"): evaluation_config_dict = { "evaluation_task": evaluation_task, - "center_distance_thresholds": [ - 100, - 200, - ], # = [[100, 100, 100, 100], [200, 200, 200, 200]] + "center_distance_thresholds": [100, 200], # = [[100, 100, 100, 100], [200, 200, 200, 200]] "iou_2d_thresholds": [0.5], # = [[0.5, 0.5, 0.5, 0.5]] } elif evaluation_task == "classification2d": @@ -59,15 +56,7 @@ def __init__( # If target_labels = None, all labels will be evaluated. evaluation_config_dict.update( dict( - target_labels=[ - "green", - "red", - "yellow", - "unknown", - "crosswalk_green", - "crosswalk_red", - "crosswalk_unknown", - ] + target_labels=["green", "red", "yellow", "unknown"] if label_prefix == "traffic_light" else ["car", "bicycle", "pedestrian", "motorbike"], ignore_attributes=["cycle_state.without_rider"] if label_prefix == "autoware" else None, @@ -114,14 +103,12 @@ def callback( # 1 frameの評価 target_labels = ( - ["green", "red", "yellow", "unknown", "crosswalk_green", "crosswalk_red", "crosswalk_unknown"] + ["green", "red", "yellow", "unknown"] if self.label_prefix == "traffic_light" else ["car", "bicycle", "pedestrian", "motorbike"] ) ignore_attributes = ["cycle_state.without_rider"] if self.label_prefix == "autoware" else None - matching_threshold_list = ( - None if self.evaluation_task == "classification2d" else [0.5, 0.5, 0.5, 0.5, 0.5, 0.5, 0.5] - ) + matching_threshold_list = None if self.evaluation_task == "classification2d" else [0.5, 0.5, 0.5, 0.5] # 距離などでUC評価objectを選別するためのインターフェイス(PerceptionEvaluationManager初期化時にConfigを設定せず、関数受け渡しにすることで動的に変更可能なInterface) # どれを注目物体とするかのparam critical_object_filter_config: CriticalObjectFilterConfig = CriticalObjectFilterConfig( From 0d096b2e725422e84ae97ba9d74e85a2d8583e17 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Mon, 4 Dec 2023 13:22:59 +0900 Subject: [PATCH 17/27] fix: remove checking label while matching objects for classification Signed-off-by: ktro2828 --- .../evaluation/result/object_result.py | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 0bb4f706..b7e835a7 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -386,11 +386,7 @@ def _get_object_results_with_id( raise RuntimeError( f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" ) - if ( - est_object.uuid == gt_object.uuid - and est_object.semantic_label == gt_object.semantic_label - and est_object.frame_id == gt_object.frame_id - ): + if est_object.uuid == gt_object.uuid and est_object.frame_id == gt_object.frame_id: object_results.append( DynamicObjectWithPerceptionResult( estimated_object=est_object, @@ -427,7 +423,11 @@ def _get_object_results_for_tlr( ground_truth_objects_ = ground_truth_objects.copy() for est_object in estimated_objects: for gt_object in ground_truth_objects_: - if est_object.uuid == gt_object.uuid and est_object.semantic_label == gt_object.semantic_label: + if est_object.uuid is None or gt_object.uuid is None: + raise RuntimeError( + f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" + ) + if est_object.uuid == gt_object.uuid and est_object.frame_id == gt_object.frame_id: object_results.append( DynamicObjectWithPerceptionResult( estimated_object=est_object, @@ -436,10 +436,6 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) - logging.info( - f"[OK] Est: {est_object.semantic_label.label}:{est_object.uuid}, " - f"GT: {gt_object.semantic_label.label}:{gt_object.uuid}" - ) # when there are rest of a GT objects, one of the estimated objects is FP. if 0 < len(ground_truth_objects_): object_results += _get_fp_object_results([estimated_objects_[0]]) From adf88b7c6d9a53a17d216d7b21165572ee8863c6 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Dec 2023 06:30:51 +0900 Subject: [PATCH 18/27] feat: update matching policy as same label first Signed-off-by: ktro2828 --- .../evaluation/result/object_result.py | 33 +++++++++++++++---- 1 file changed, 27 insertions(+), 6 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index b7e835a7..0d5ff1bb 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -14,7 +14,6 @@ from __future__ import annotations -import logging from typing import Callable from typing import List from typing import Optional @@ -381,7 +380,7 @@ def _get_object_results_with_id( estimated_objects_ = estimated_objects.copy() ground_truth_objects_ = ground_truth_objects.copy() for est_object in estimated_objects: - for gt_object in ground_truth_objects_: + for gt_object in ground_truth_objects: if est_object.uuid is None or gt_object.uuid is None: raise RuntimeError( f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" @@ -421,12 +420,37 @@ def _get_object_results_for_tlr( object_results: List[DynamicObjectWithPerceptionResult] = [] estimated_objects_ = estimated_objects.copy() ground_truth_objects_ = ground_truth_objects.copy() + # 1. matching based on same label primary for est_object in estimated_objects: - for gt_object in ground_truth_objects_: + for gt_object in ground_truth_objects: if est_object.uuid is None or gt_object.uuid is None: raise RuntimeError( f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" ) + + if ( + est_object.uuid == gt_object.uuid + and est_object.frame_id == gt_object.frame_id + and est_object.semantic_label == gt_object.semantic_label + ): + object_results.append( + DynamicObjectWithPerceptionResult( + estimated_object=est_object, + ground_truth_object=gt_object, + ) + ) + estimated_objects_.remove(est_object) + ground_truth_objects_.remove(gt_object) + # 2. matching based on same ID + rest_estimated_objects_ = estimated_objects_.copy() + rest_ground_truth_objects_ = ground_truth_objects_.copy() + for est_object in rest_estimated_objects_: + for gt_object in rest_ground_truth_objects_: + if est_object.uuid is None or gt_object.uuid is None: + raise RuntimeError( + f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" + ) + if est_object.uuid == gt_object.uuid and est_object.frame_id == gt_object.frame_id: object_results.append( DynamicObjectWithPerceptionResult( @@ -436,9 +460,6 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) - # when there are rest of a GT objects, one of the estimated objects is FP. - if 0 < len(ground_truth_objects_): - object_results += _get_fp_object_results([estimated_objects_[0]]) return object_results From 97f9e2dcd8ec87e5fa9a2c0581f1ee6bfc65fe95 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Dec 2023 06:37:57 +0900 Subject: [PATCH 19/27] test: fix label test for TLR Signed-off-by: ktro2828 --- perception_eval/perception_eval/common/label.py | 1 + perception_eval/test/common/test_label.py | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/perception_eval/perception_eval/common/label.py b/perception_eval/perception_eval/common/label.py index 2bf27ff1..49a1f4ef 100644 --- a/perception_eval/perception_eval/common/label.py +++ b/perception_eval/perception_eval/common/label.py @@ -381,6 +381,7 @@ def _get_traffic_light_paris( ] else: pair_list: List[Tuple[TrafficLightLabel, str]] = [ + (TrafficLightLabel.TRAFFIC_LIGHT, "traffic_light"), (TrafficLightLabel.TRAFFIC_LIGHT, "green"), (TrafficLightLabel.TRAFFIC_LIGHT, "green_straight"), (TrafficLightLabel.TRAFFIC_LIGHT, "green_left"), diff --git a/perception_eval/test/common/test_label.py b/perception_eval/test/common/test_label.py index 3ea259b1..d7fd633f 100644 --- a/perception_eval/test/common/test_label.py +++ b/perception_eval/test/common/test_label.py @@ -65,10 +65,10 @@ (TrafficLightLabel.YELLOW, "yellow"), (TrafficLightLabel.RED_STRAIGHT, "red_straight"), (TrafficLightLabel.RED_LEFT, "red_left"), - (TrafficLightLabel.RED_STRAIGHT_LEFT, "red_left_straight"), + (TrafficLightLabel.RED_STRAIGHT_LEFT, "red_straight_left"), (TrafficLightLabel.RED_LEFT_DIAGONAL, "red_left_diagonal"), (TrafficLightLabel.RED_RIGHT, "red_right"), - (TrafficLightLabel.RED_STRAIGHT_RIGHT, "red_right_straight"), + (TrafficLightLabel.RED_STRAIGHT_RIGHT, "red_straight_right"), (TrafficLightLabel.RED_RIGHT_DIAGONAL, "red_right_diagonal"), (TrafficLightLabel.YELLOW_RIGHT, "yellow_right"), (TrafficLightLabel.UNKNOWN, "unknown"), From 2e9acb7c7fad3a4182cc8a37c3b4cdfc739ef081 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Dec 2023 09:19:25 +0900 Subject: [PATCH 20/27] fix: TODO update matching policy Signed-off-by: ktro2828 --- .../evaluation/result/object_result.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 0d5ff1bb..036a16eb 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -421,6 +421,7 @@ def _get_object_results_for_tlr( estimated_objects_ = estimated_objects.copy() ground_truth_objects_ = ground_truth_objects.copy() # 1. matching based on same label primary + # NOTE: current implementation match Est/Gt pairs without considering ID, therefore it might not be right result for est_object in estimated_objects: for gt_object in ground_truth_objects: if est_object.uuid is None or gt_object.uuid is None: @@ -429,9 +430,10 @@ def _get_object_results_for_tlr( ) if ( - est_object.uuid == gt_object.uuid + est_object.semantic_label == gt_object.semantic_label and est_object.frame_id == gt_object.frame_id - and est_object.semantic_label == gt_object.semantic_label + and est_object in estimated_objects_ + and gt_object in ground_truth_objects_ ): object_results.append( DynamicObjectWithPerceptionResult( @@ -441,6 +443,7 @@ def _get_object_results_for_tlr( ) estimated_objects_.remove(est_object) ground_truth_objects_.remove(gt_object) + # 2. matching based on same ID rest_estimated_objects_ = estimated_objects_.copy() rest_ground_truth_objects_ = ground_truth_objects_.copy() @@ -451,7 +454,12 @@ def _get_object_results_for_tlr( f"uuid of estimation and ground truth must be set, but got {est_object.uuid} and {gt_object.uuid}" ) - if est_object.uuid == gt_object.uuid and est_object.frame_id == gt_object.frame_id: + if ( + est_object.uuid == gt_object.uuid + and est_object.frame_id == gt_object.frame_id + and est_object in estimated_objects_ + and gt_object in ground_truth_objects_ + ): object_results.append( DynamicObjectWithPerceptionResult( estimated_object=est_object, From 69502d5c63098bc896e0084208ac636f5e05647b Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 1 May 2024 18:14:59 +0900 Subject: [PATCH 21/27] refactor: clean code and remove simple_lanelet_loader Signed-off-by: ktro2828 --- .../perception_eval/common/dataset.py | 2 - .../perception_eval/common/dataset_utils.py | 1 - show_fail_data.py | 70 ------------ simple_lanelet_loader/CMakeLists.txt | 10 -- simple_lanelet_loader/package.xml | 18 --- .../simple_lanelet_loader/__init__.py | 0 .../traffic_light_loader.py | 106 ------------------ simple_lanelet_loader/test_map_load.py | 35 ------ 8 files changed, 242 deletions(-) delete mode 100644 show_fail_data.py delete mode 100644 simple_lanelet_loader/CMakeLists.txt delete mode 100644 simple_lanelet_loader/package.xml delete mode 100644 simple_lanelet_loader/simple_lanelet_loader/__init__.py delete mode 100644 simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py delete mode 100644 simple_lanelet_loader/test_map_load.py diff --git a/perception_eval/perception_eval/common/dataset.py b/perception_eval/perception_eval/common/dataset.py index 7e9100c6..026a3cb2 100644 --- a/perception_eval/perception_eval/common/dataset.py +++ b/perception_eval/perception_eval/common/dataset.py @@ -285,8 +285,6 @@ def get_now_frame( if diff_time < min_time: ground_truth_now_frame = ground_truth_frame min_time = diff_time - # if 0 < len(ground_truth_frame.objects) and (any([obj.uuid in ("10321", "179948") for obj in ground_truth_frame.objects]) and diff_time < threshold_min_time or ground_truth_frame.objects[0].uuid == "10321"): - # logging.info(f"uuids: {[obj.uuid for obj in ground_truth_frame.objects]}, diff time: {diff_time / 1000}") if min_time > threshold_min_time: logging.info( f"Now frame is {ground_truth_now_frame.unix_time} and time difference \ diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 15c204a2..4548dd5c 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -14,7 +14,6 @@ from __future__ import annotations -import logging from typing import Any from typing import Dict from typing import List diff --git a/show_fail_data.py b/show_fail_data.py deleted file mode 100644 index 5afcfecc..00000000 --- a/show_fail_data.py +++ /dev/null @@ -1,70 +0,0 @@ -import argparse -import json -import os.path as osp - -import cv2 - - -def main(): - parser = argparse.ArgumentParser() - parser.add_argument("fail_info", type=str, help="path of fail_info.json") - parser.add_argument("data", type=str, help="root path of dataset") - args = parser.parse_args() - - with open(args.fail_info, "r") as f: - fail_records = json.load(f) - - with open(osp.join(args.data, "annotation/sample_data.json"), "r") as f: - sample_data_records = json.load(f) - - print(f"Num Fail: {len(fail_records)}") - - for fail_info in fail_records: - timestamp = fail_info["timestamp"] - sample_data = None - for sd_record in sample_data_records: - if sd_record["timestamp"] == timestamp: - sample_data = sd_record - if sample_data is None: - print(f"[WARN]: There is no corresponding sample data!!, timestamp: {timestamp}") - continue - filename = sample_data["filename"] - img = cv2.imread(osp.join(args.data, filename)) - for fp_result in fail_info.get("fp", []): - img = cv2.putText( - img, - text=f"[FP-Est]: {fp_result['est']}", - org=(30, 30), - fontFace=cv2.FONT_HERSHEY_SIMPLEX, - fontScale=1.0, - color=(255, 255, 255), - ) - img = cv2.putText( - img, - text=f"[FP-GT]: {fp_result['gt']}", - org=(50, 50), - fontFace=cv2.FONT_HERSHEY_SIMPLEX, - fontScale=1.0, - color=(0, 0, 255), - ) - - for fn_result in fail_info.get("fn", []): - img = cv2.putText( - img, - text=f"[FN-GT]: {fn_result['gt']}", - org=(100, 100), - fontFace=cv2.FONT_HERSHEY_SIMPLEX, - fontScale=1.0, - color=(0, 0, 255), - ) - - cv2.imshow("img", img) - key = cv2.waitKey(0) - cv2.destroyAllWindows() - - if key == 27: - break - - -if __name__ == "__main__": - main() diff --git a/simple_lanelet_loader/CMakeLists.txt b/simple_lanelet_loader/CMakeLists.txt deleted file mode 100644 index a0b0d868..00000000 --- a/simple_lanelet_loader/CMakeLists.txt +++ /dev/null @@ -1,10 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(simple_lanelet_loader) - -find_package(ament_cmake_auto REQUIRED) -find_package(ament_cmake_python REQUIRED) -ament_auto_find_build_dependencies() - -ament_python_install_package(${PROJECT_NAME}) - -ament_auto_package() diff --git a/simple_lanelet_loader/package.xml b/simple_lanelet_loader/package.xml deleted file mode 100644 index 58068f22..00000000 --- a/simple_lanelet_loader/package.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - simple_lanelet_loader - 1.0.7 - simple lanelet loader for logsim - Shunsuke Miura - Apache V2 - - ament_copyright - ament_flake8 - ament_pep257 - python3-pytest - - - ament_cmake - - diff --git a/simple_lanelet_loader/simple_lanelet_loader/__init__.py b/simple_lanelet_loader/simple_lanelet_loader/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py b/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py deleted file mode 100644 index 70c2b207..00000000 --- a/simple_lanelet_loader/simple_lanelet_loader/traffic_light_loader.py +++ /dev/null @@ -1,106 +0,0 @@ -import logging -from typing import Dict -from typing import List -from typing import Optional -import xml.etree.ElementTree as ET # noqa - -import numpy as np - - -class TrafficLightLoader: - def __init__(self, map_path) -> None: - tree = ET.parse(map_path) - root = tree.getroot() - - # 1. extract node, way relation from xml - self.nodes = {} - self.traffic_light_ways = {} - self.traffic_light_regulatory_elements = {} - - for child in root: - if child.tag == "node": - ref_id, x, y, z = extract_node(child) - self.nodes[ref_id] = [x, y, z] - elif child.tag == "way": - traffic_light_way = extract_traffic_light_way(child) - if traffic_light_way: - self.traffic_light_ways |= traffic_light_way - elif child.tag == "relation": - # ids = int(child.attrib["id"]) - element = extract_traffic_light_regulatory_element(child) - if element: - self.traffic_light_regulatory_elements |= element - - self.traffic_light_positions = {} - for id, refs in self.traffic_light_ways.items(): - traffic_light_position = np.array([0.0, 0.0, 0.0]) - for ref_id in refs: - traffic_light_position += np.array(self.nodes[ref_id]) - self.traffic_light_positions[id] = traffic_light_position / 2 - - def get_distance_to_traffic_light_group(self, regulatory_element_id, origin): - distance = 10000 - origin = np.array(origin) - logging.info(f"regulatory_element_id: {regulatory_element_id}") - for id, refers in self.traffic_light_regulatory_elements.items(): - if id == regulatory_element_id: - logging.info(f"id:{id}, refers:{refers}") - for ref_id in refers: - if ref_id not in self.traffic_light_positions.keys(): - continue - try: - traffic_light_position = self.traffic_light_positions[ref_id] - # logging.info(f"traffic_light_position: {traffic_light_position}, {traffic_light_position-origin}") - dist = np.linalg.norm(traffic_light_position - origin) - # logging.info(f"distance={dist}") - if dist < distance: - distance = dist - except KeyError: - logging.info(f"KeyError: @{regulatory_element_id}") - - return distance - - -""" utils for map-loader program""" - - -def extract_node(child): - x, y, z = 0, 0, 0 - for tag in child: - if tag.attrib["k"] == "local_x": - x = tag.attrib["v"] - elif tag.attrib["k"] == "local_y": - y = tag.attrib["v"] - elif tag.attrib["k"] == "ele": - z = tag.attrib["v"] - return child.attrib["id"], float(x), float(y), float(z) - - -def extract_traffic_light_way(child): - refs = [] - # tags = {} - for tag in child: - if tag.tag == "nd": - refs.append(tag.attrib["ref"]) - # elif tag.attrib["k"] == "type": - # if tag.attrib["v"] == "traffic_light": - elif tag.attrib["k"] == "subtype": - if tag.attrib["v"] == "red_yellow_green": - return {child.attrib["id"]: refs} - - -def extract_traffic_light_regulatory_element(child) -> Optional[Dict[str, List[int]]]: - refers = [] - for tag in child: - if tag.tag == "member": - if tag.attrib["role"] == "refers": - refers.append(tag.attrib["ref"]) - if tag.tag == "tag": - if tag.attrib["k"] == "type" and tag.attrib["v"] == "regulatory_element": - continue - elif tag.attrib["k"] == "subtype" and tag.attrib["v"] == "traffic_light": - continue - else: - return - regulatory_element = {child.attrib["id"]: refers} - return regulatory_element diff --git a/simple_lanelet_loader/test_map_load.py b/simple_lanelet_loader/test_map_load.py deleted file mode 100644 index 3c793414..00000000 --- a/simple_lanelet_loader/test_map_load.py +++ /dev/null @@ -1,35 +0,0 @@ -import os - -import numpy as np - -from simple_lanelet_loader.traffic_light_loader import TrafficLightLoader - -default_map_path = "~/lanelet2_map.osm" - - -def refine_path(path): - # fix ~ - path = os.path.expanduser(path) - # fix $HOME - path = os.path.expandvars(path) - return path - - -def main(map_path: str): - # load map obj - map_obj = TrafficLightLoader(map_path) - print(map_obj.get_distance_to_traffic_light_group("179563", np.array([89434.6492, 42630.8311, 5.686]))) - - print(map_obj) - - -if __name__ == "__main__": - import argparse - - parser = argparse.ArgumentParser() - parser.add_argument("--map_path", type=str, default=default_map_path) - - # get args - args = parser.parse_args() - map_path = refine_path(args.map_path) - main(map_path) From 8c0f97b8130e1af794cda3b4af6360bdcb6283a8 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 9 May 2024 00:26:17 +0900 Subject: [PATCH 22/27] feat: add support of filter out the 2D object by its position Signed-off-by: ktro2828 --- .../perception_eval/common/dataset.py | 5 +- .../perception_eval/common/dataset_utils.py | 47 ++++++++++--------- .../perception_eval/common/object.py | 22 ++++----- .../perception_eval/common/object2d.py | 31 ++++++++++++ .../evaluation/matching/objects_filter.py | 16 +++---- perception_eval/perception_eval/tool/utils.py | 25 ++++++++-- perception_eval/perception_eval/util/debug.py | 23 +++++++++ .../visualization/perception_visualizer2d.py | 2 +- perception_eval/test/perception_lsim2d.py | 47 +++++++++++++------ 9 files changed, 153 insertions(+), 65 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset.py b/perception_eval/perception_eval/common/dataset.py index b86bc319..60241aa3 100644 --- a/perception_eval/perception_eval/common/dataset.py +++ b/perception_eval/perception_eval/common/dataset.py @@ -32,7 +32,6 @@ from perception_eval.common.geometry import interpolate_homogeneous_matrix from perception_eval.common.geometry import interpolate_object_list from perception_eval.common.label import LabelConverter -from perception_eval.common.object import DynamicObject from perception_eval.common.schema import FrameID from perception_eval.common.transform import HomogeneousMatrix from perception_eval.common.transform import TransformDict @@ -48,7 +47,7 @@ def __init__( self, unix_time: int, frame_name: str, - objects: List[DynamicObject], + objects: List[ObjectType], transforms: TransformDictArgType = None, raw_data: Optional[Dict[FrameID, NDArray]] = None, ) -> None: @@ -56,7 +55,7 @@ def __init__( Args: unix_time (int): Current unix time. frame_name (str): The file name - objects (list[DynamicObject]): Ground truth objects. + objects (list[ObjectType]): Ground truth objects. transforms (TransformDict | None, optional): 4x4 transform matrices. Defaults to None. raw_data (dict[FrameID, NDArray] | None, optional): Raw data for each sensor. Defaults to None. """ diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index eca0215f..9b16745c 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -91,7 +91,7 @@ def _sample_to_frame( raise ValueError("lidar data isn't found") object_boxes = _get_sample_boxes(nusc, sample_data_token, frame_id) - transforms = _get_transforms(nusc, sample_data_token) + transforms = _get_transforms(nusc, sample_data_token, evaluation_task, label_converter.label_type) raw_data = _load_raw_data(nusc, sample_token) if load_raw_data else None objects_: List[DynamicObject] = [] @@ -251,6 +251,7 @@ def _get_sample_boxes(nusc: NuScenes, sample_data_token: str, frame_id: FrameID) def _get_transforms(nusc: NuScenes, sample_data_token: str) -> List[HomogeneousMatrix]: """Load transform matrices. + Additionally, for traffic light cameras, add transforms from BASE_LINK to TRAFFIC_LIGHT. Args: nusc (NuScenes): NuScenes instance. @@ -275,6 +276,14 @@ def _get_transforms(nusc: NuScenes, sample_data_token: str) -> List[HomogeneousM ego2sensor = HomogeneousMatrix(sensor_position, sensor_rotation, src=FrameID.BASE_LINK, dst=sensor_frame_id) sensor2map = ego2sensor.inv().dot(ego2map) matrices.extend((ego2sensor, sensor2map)) + # TODO: A transform BASE_LINK->TRAFFIC_LIGHT would be overwritten if the dataset contains multiple TLR cameras. + if "CAM_TRAFFIC_LIGHT" in sensor_frame_id.value.upper(): + ego2tlr = HomogeneousMatrix( + sensor_position, sensor_rotation, src=FrameID.BASE_LINK, dst=FrameID.TRAFFIC_LIGHT + ) + tlr2map = ego2tlr.inv().dot(ego2map) + matrices.extend((ego2tlr, tlr2map)) + return matrices @@ -477,26 +486,18 @@ def _sample_to_frame_2d( sample_data_tokens: List[str] = [] frame_id_mapping: Dict[str, FrameID] = {} + transforms = None for frame_id_ in frame_ids: - # TODO update - scene_descriptions: List[str] = nusc.get("scene", sample["scene_token"])["description"].split(", ") - if "regulatory_element" in scene_descriptions: - for camera_type in ( - FrameID.CAM_TRAFFIC_LIGHT_FAR.value.upper(), - FrameID.CAM_TRAFFIC_LIGHT_NEAR.value.upper(), - ): - if nusc_sample["data"].get(camera_type) is None: - continue - sample_data_token = nusc_sample["data"][camera_type] - sample_data_tokens.append(sample_data_token) - frame_id_mapping[sample_data_token] = FrameID.TRAFFIC_LIGHT - else: - camera_type: str = frame_id_.value.upper() - if nusc_sample["data"].get(camera_type) is None: - continue - sample_data_token = nusc_sample["data"][camera_type] - sample_data_tokens.append(sample_data_token) - frame_id_mapping[sample_data_token] = frame_id_ + camera_type: str = frame_id_.value.upper() + if nusc_sample["data"].get(camera_type) is None: + continue + sample_data_token = nusc_sample["data"][camera_type] + sample_data_tokens.append(sample_data_token) + frame_id_mapping[sample_data_token] = frame_id_ + + sd_record = nusc.get("sample_data", sample_data_token) + if sd_record["is_key_frame"]: + transforms = _get_transforms(nusc, sample_data_token) if load_raw_data: raw_data = _load_raw_data(nusc, sample_token) @@ -556,6 +557,7 @@ def _sample_to_frame_2d( unix_time=unix_time, frame_name=frame_name, objects=objects_, + transforms=transforms, raw_data=raw_data, ) @@ -567,7 +569,7 @@ def _merge_duplicated_traffic_lights( objects: List[DynamicObject2D], uuids: List[str], ) -> List[DynamicObject2D]: - """Merge traffic light objects which have same uuid. + """Merge traffic light objects which have same uuids and set its frame id as `FrameID.TRAFFIC_LIGHT`. Args: unix_time (int): Current unix timestamp. @@ -596,7 +598,7 @@ def _merge_duplicated_traffic_lights( assert semantic_label.label != TrafficLightLabel.UNKNOWN merged_object = DynamicObject2D( unix_time=unix_time, - frame_id=candidates[0].frame_id, + frame_id=FrameID.TRAFFIC_LIGHT, semantic_score=1.0, semantic_label=semantic_label, roi=None, @@ -604,5 +606,4 @@ def _merge_duplicated_traffic_lights( visibility=None, ) ret_objects.append(merged_object) - assert len(ret_objects) == len(set([obj.uuid for obj in ret_objects])) return ret_objects diff --git a/perception_eval/perception_eval/common/object.py b/perception_eval/perception_eval/common/object.py index ab6a7ca3..b6f5c513 100644 --- a/perception_eval/perception_eval/common/object.py +++ b/perception_eval/perception_eval/common/object.py @@ -50,27 +50,27 @@ class ObjectState: def __init__( self, - position: Tuple[float, float, float], - orientation: Quaternion, - shape: Shape, + position: Optional[Tuple[float, float, float]], + orientation: Optional[Quaternion], + shape: Optional[Shape], velocity: Optional[Tuple[float, float, float]], ) -> None: - self.position: Tuple[float, float, float] = position - self.orientation: Quaternion = orientation - self.shape: Shape = shape - self.velocity: Optional[Tuple[float, float, float]] = velocity + self.position = position + self.orientation = orientation + self.shape = shape + self.velocity = velocity @property - def shape_type(self) -> ShapeType: - return self.shape.type + def shape_type(self) -> Optional[ShapeType]: + return self.shape.type if self.shape is not None else None @property def size(self) -> Tuple[float, float, float]: - return self.shape.size + return self.shape.size if self.shape is not None else None @property def footprint(self) -> Polygon: - return self.shape.footprint + return self.shape.footprint if self.shape is not None else None class DynamicObject: diff --git a/perception_eval/perception_eval/common/object2d.py b/perception_eval/perception_eval/common/object2d.py index 678ec203..7252aa3f 100644 --- a/perception_eval/perception_eval/common/object2d.py +++ b/perception_eval/perception_eval/common/object2d.py @@ -14,14 +14,17 @@ from __future__ import annotations +import math from typing import List from typing import Optional from typing import Tuple import numpy as np from perception_eval.common.label import Label +from perception_eval.common.object import ObjectState from perception_eval.common.schema import FrameID from perception_eval.common.schema import Visibility +from perception_eval.common.transform import TransformDict from shapely.geometry import Polygon @@ -124,6 +127,7 @@ class DynamicObject2D: For classification, None is OK. Defaults to None. uuid (Optional[str]): Unique ID. For traffic light objects, set lane ID. Defaults to None. visibility (Optional[Visibility]): Visibility status. Defaults to None. + position (Optional[Tuple[float, float, float]]): 3D position in ordering (x, y, z). Defaults to None. """ def __init__( @@ -135,6 +139,7 @@ def __init__( roi: Optional[Tuple[int, int, int, int]] = None, uuid: Optional[str] = None, visibility: Optional[Visibility] = None, + position: Optional[Tuple[float, float, float]] = None, ) -> None: super().__init__() self.unix_time: int = unix_time @@ -144,6 +149,7 @@ def __init__( self.roi: Optional[Roi] = Roi(roi) if roi is not None else None self.uuid: Optional[str] = uuid self.visibility: Optional[Visibility] = visibility + self.state = ObjectState(position, None, None, None) def get_corners(self) -> np.ndarray: """Returns the corners of bounding box in pixel. @@ -176,3 +182,28 @@ def get_polygon(self) -> Polygon: corners: List[List[float]] = self.get_corners().tolist() corners.append(corners[0]) return Polygon(corners) + + def set_position(self, position: Tuple[float, float, float]) -> None: + """Set 3D position value. + + Args: + position (Tuple[float, float, float]): 3D position in ordering (x, y, z). + """ + self.state.position = position + + def get_distance_bev(self, transforms: Optional[TransformDict] = None) -> float: + """Get the 2d distance to the object from ego vehicle in bird eye view. + + Args: + + Returns: + float: The 2d distance to the object from ego vehicle in bird eye view. + """ + assert self.state.position is not None, "self.state.position must be set." + if self.frame_id == FrameID.BASE_LINK: + position = self.state.position + else: + if transforms is None: + raise ValueError("transforms must be specified.") + position = transforms.transform((self.frame_id, FrameID.BASE_LINK), self.state.position) + return math.hypot(position[0], position[1]) diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index 804e4b0e..1e316cc8 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -23,6 +23,7 @@ from perception_eval.common.label import CommonLabel from perception_eval.common.label import Label from perception_eval.common.label import LabelType +from perception_eval.common.object2d import DynamicObject2D from perception_eval.common.object import DynamicObject from perception_eval.common.schema import FrameID from perception_eval.common.status import MatchingStatus @@ -543,14 +544,13 @@ def _is_target_object( ) is_target = is_target and dynamic_object.semantic_score > confidence_threshold - if isinstance(dynamic_object, DynamicObject): - if dynamic_object.frame_id != FrameID.BASE_LINK: - position_ = transforms.transform( - (dynamic_object.frame_id, FrameID.BASE_LINK), dynamic_object.state.position - ) - else: - position_ = dynamic_object.state.position + if dynamic_object.state.position is not None: + position_ = transforms.transform((dynamic_object.frame_id, FrameID.BASE_LINK), dynamic_object.state.position) + bev_distance_ = dynamic_object.get_distance_bev(transforms) + else: + position_ = bev_distance_ = None + if position_ is not None: if is_target and max_x_position_list is not None: max_x_position = ( max_x_position_list[0] @@ -567,7 +567,7 @@ def _is_target_object( ) is_target = is_target and abs(position_[1]) < max_y_position - bev_distance_: float = dynamic_object.get_distance_bev(transforms) + if bev_distance_ is not None: if is_target and max_distance_list is not None: max_distance = ( max_distance_list[0] diff --git a/perception_eval/perception_eval/tool/utils.py b/perception_eval/perception_eval/tool/utils.py index 6b01f9ec..680826a3 100644 --- a/perception_eval/perception_eval/tool/utils.py +++ b/perception_eval/perception_eval/tool/utils.py @@ -462,13 +462,30 @@ def get_aligned_timestamp(df: pd.DataFrame) -> np.ndarray: def filter_frame_by_distance( frame: PerceptionFrameResult, - min_distance: Optional[float], - max_distance: Optional[float], + min_distance: Optional[float] = None, + max_distance: Optional[float] = None, ) -> PerceptionFrameResult: + """Filter frame results by distance. + + Args: + frame (PerceptionFrameResult): Frame result. + min_distance (Optional[float], optional): Min distance range. Defaults to None. + max_distance (Optional[float], optional): Max distance range. Defaults to None. + + Returns: + PerceptionFrameResult: Filtered frame results. + """ ret_frame = deepcopy(frame) - min_distance_list = [min_distance] * len(ret_frame.target_labels) - max_distance_list = [max_distance] * len(ret_frame.target_labels) + if min_distance is not None: + min_distance_list = [min_distance] * len(ret_frame.target_labels) + else: + min_distance_list = None + + if max_distance is not None: + max_distance_list = [max_distance] * len(ret_frame.target_labels) + else: + max_distance_list = None ret_frame.object_results = filter_object_results( ret_frame.object_results, diff --git a/perception_eval/perception_eval/util/debug.py b/perception_eval/perception_eval/util/debug.py index 9726a6c5..93790235 100644 --- a/perception_eval/perception_eval/util/debug.py +++ b/perception_eval/perception_eval/util/debug.py @@ -15,16 +15,21 @@ from enum import Enum import pprint import random +from typing import Dict from typing import List from typing import Optional from typing import Tuple +import numpy as np +from numpy.typing import ArrayLike +from perception_eval.common.dataset import FrameGroundTruth from perception_eval.common.label import AutowareLabel from perception_eval.common.label import Label from perception_eval.common.label import LabelType from perception_eval.common.label import TrafficLightLabel from perception_eval.common.object2d import DynamicObject2D from perception_eval.common.object import DynamicObject +from perception_eval.common.schema import FrameID from perception_eval.common.shape import Shape from perception_eval.common.transform import TransformDict from pyquaternion.quaternion import Quaternion @@ -263,3 +268,21 @@ def get_objects_with_difference2d( ) ) return output_objects + + +def get_random_position_map(frame_ground_truth: FrameGroundTruth) -> Dict[str, ArrayLike]: + """Return a container storing positions of corresponding uuids randomly. + + The positions are computed as ego position + random * 100.0. + + Args: + frame_ground_truth (FrameGroundTruth): + + Returns: + Dict[str, ArrayLike]: Position map. + """ + output: Dict[str, ArrayLike] = {} + ego2map = frame_ground_truth.transforms[(FrameID.BASE_LINK, FrameID.MAP)] + for obj in frame_ground_truth.objects: + output[obj.uuid] = np.random.rand(3) * 100.0 + ego2map.position + return output diff --git a/perception_eval/perception_eval/visualization/perception_visualizer2d.py b/perception_eval/perception_eval/visualization/perception_visualizer2d.py index 433972f5..3a1302eb 100644 --- a/perception_eval/perception_eval/visualization/perception_visualizer2d.py +++ b/perception_eval/perception_eval/visualization/perception_visualizer2d.py @@ -116,7 +116,7 @@ def init_figure(self) -> Tuple[Figure, np.ndarray]: self.label_type: Union[AutowareLabel, TrafficLightLabel] = self.__config.label_converter.label_type if self.label_type == TrafficLightLabel: - cameras = ("cam_traffic_light_near", "cam_traffic_light_far", "traffic_light") + cameras = ("cam_traffic_light_near", "cam_traffic_light_far") fig, axes = plt.subplots(1, 2, figsize=self.__figsize, gridspec_kw=dict(wspace=0)) elif self.label_type == AutowareLabel: cameras = ( diff --git a/perception_eval/test/perception_lsim2d.py b/perception_eval/test/perception_lsim2d.py index b274571e..ecf2e3b7 100644 --- a/perception_eval/test/perception_lsim2d.py +++ b/perception_eval/test/perception_lsim2d.py @@ -27,6 +27,7 @@ from perception_eval.manager import PerceptionEvaluationManager from perception_eval.tool import PerceptionAnalyzer2D from perception_eval.util.debug import get_objects_with_difference2d +from perception_eval.util.debug import get_random_position_map from perception_eval.util.logger_config import configure_logger @@ -54,14 +55,22 @@ def __init__( raise ValueError(f"Unexpected evaluation task: {evaluation_task}") # If target_labels = None, all labels will be evaluated. - evaluation_config_dict.update( - dict( - target_labels=["green", "red", "yellow", "unknown"] - if label_prefix == "traffic_light" - else ["car", "bicycle", "pedestrian", "motorbike"], - ignore_attributes=["cycle_state.without_rider"] if label_prefix == "autoware" else None, + if self.label_prefix == "autoware": + evaluation_config_dict.update( + dict( + target_labels=["car", "bicycle", "pedestrian", "motorbike"], + ignore_attributes=["cycle_state.without_rider"], + ) ) - ) + elif self.label_prefix == "traffic_light": + evaluation_config_dict.update( + dict( + target_labels=["green", "red", "yellow", "unknown"], + max_distance=150.0, + min_distance=0.0, + ) + ) + evaluation_config_dict.update( dict( allow_matching_unknown=True, @@ -76,7 +85,7 @@ def __init__( frame_id=camera_type, result_root_directory=result_root_directory, evaluation_config_dict=evaluation_config_dict, - load_raw_data=True, + load_raw_data=False, ) _ = configure_logger( @@ -95,19 +104,27 @@ def callback( # 現frameに対応するGround truthを取得 ground_truth_now_frame = self.evaluator.get_ground_truth_now_frame(unix_time) + # 1 frameの評価 + if self.label_prefix == "traffic_light": + target_labels = ["green", "red", "yellow", "unknown"] + ignore_attributes = None # example + # set position from map which hash position of corresponding uuid. + position_uuid_map = get_random_position_map(ground_truth_now_frame) + for obj in ground_truth_frame.objects: + position = position_uuid_map[obj.uuid] + obj.set_position(position) + elif self.label_prefix == "autoware": + target_labels = ["car", "bicycle", "pedestrian", "motorbike"] + ignore_attributes = ["cycle_state.without_rider"] # example + else: + raise ValueError(f"Unexpected label prefix: {self.label_prefix}") + # [Option] ROS側でやる(Map情報・Planning結果を用いる)UC評価objectを選別 # ros_critical_ground_truth_objects : List[DynamicObject] = custom_critical_object_filter( # ground_truth_now_frame.objects # ) ros_critical_ground_truth_objects = ground_truth_now_frame.objects - # 1 frameの評価 - target_labels = ( - ["green", "red", "yellow", "unknown"] - if self.label_prefix == "traffic_light" - else ["car", "bicycle", "pedestrian", "motorbike"] - ) - ignore_attributes = ["cycle_state.without_rider"] if self.label_prefix == "autoware" else None matching_threshold_list = None if self.evaluation_task == "classification2d" else [0.5, 0.5, 0.5, 0.5] # 距離などでUC評価objectを選別するためのインターフェイス(PerceptionEvaluationManager初期化時にConfigを設定せず、関数受け渡しにすることで動的に変更可能なInterface) # どれを注目物体とするかのparam From 340679a5be9678607a914cd57a21a687d041572e Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 14 May 2024 10:47:20 +0900 Subject: [PATCH 23/27] fix: avoid the case if `transforms` is None Signed-off-by: ktro2828 --- perception_eval/perception_eval/common/dataset_utils.py | 2 +- .../perception_eval/evaluation/matching/objects_filter.py | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 9b16745c..5179f36b 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -91,7 +91,7 @@ def _sample_to_frame( raise ValueError("lidar data isn't found") object_boxes = _get_sample_boxes(nusc, sample_data_token, frame_id) - transforms = _get_transforms(nusc, sample_data_token, evaluation_task, label_converter.label_type) + transforms = _get_transforms(nusc, sample_data_token) raw_data = _load_raw_data(nusc, sample_token) if load_raw_data else None objects_: List[DynamicObject] = [] diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index 1e316cc8..f1661b88 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -544,7 +544,10 @@ def _is_target_object( ) is_target = is_target and dynamic_object.semantic_score > confidence_threshold - if dynamic_object.state.position is not None: + if transforms is None and dynamic_object.frame_id == FrameID.BASE_LINK: + position_ = dynamic_object.state.position + bev_distance_ = dynamic_object.get_distance_bev() + elif dynamic_object.state.position is not None and transforms is not None: position_ = transforms.transform((dynamic_object.frame_id, FrameID.BASE_LINK), dynamic_object.state.position) bev_distance_ = dynamic_object.get_distance_bev(transforms) else: From 1cf9c500a4780f3dfa5a9aae008112b76e33646e Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 23 May 2024 13:09:53 +0900 Subject: [PATCH 24/27] fix: resolve wrong transformation Signed-off-by: ktro2828 --- .../perception_eval/common/dataset_utils.py | 29 ++++++++++++------- .../perception_eval/common/transform.py | 19 +++++++++--- .../evaluation/matching/objects_filter.py | 2 ++ perception_eval/test/common/test_transform.py | 28 +++++++++++++++++- 4 files changed, 62 insertions(+), 16 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 5179f36b..3f7e8928 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -29,6 +29,9 @@ from nuscenes.nuscenes import NuScenes from nuscenes.prediction.helper import PredictHelper from nuscenes.utils.data_classes import Box +from PIL import Image +from pyquaternion.quaternion import Quaternion + from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.common.label import Label from perception_eval.common.label import LabelConverter @@ -41,8 +44,6 @@ from perception_eval.common.shape import Shape from perception_eval.common.shape import ShapeType from perception_eval.common.transform import HomogeneousMatrix -from PIL import Image -from pyquaternion.quaternion import Quaternion from . import dataset @@ -268,21 +269,27 @@ def _get_transforms(nusc: NuScenes, sample_data_token: str) -> List[HomogeneousM ego2map = HomogeneousMatrix(ego_position, ego_rotation, src=FrameID.BASE_LINK, dst=FrameID.MAP) matrices = [ego2map] + tlr_avg_pos: List[NDArray] = [] + tlr_avg_quat: List[Quaternion] = [] for cs_record in nusc.calibrated_sensor: sensor_position = cs_record["translation"] sensor_rotation = Quaternion(cs_record["rotation"]) sensor_record = nusc.get("sensor", cs_record["sensor_token"]) sensor_frame_id = FrameID.from_value(sensor_record["channel"]) - ego2sensor = HomogeneousMatrix(sensor_position, sensor_rotation, src=FrameID.BASE_LINK, dst=sensor_frame_id) - sensor2map = ego2sensor.inv().dot(ego2map) - matrices.extend((ego2sensor, sensor2map)) - # TODO: A transform BASE_LINK->TRAFFIC_LIGHT would be overwritten if the dataset contains multiple TLR cameras. + sensor2ego = HomogeneousMatrix(sensor_position, sensor_rotation, src=sensor_frame_id, dst=FrameID.BASE_LINK) + sensor2map = ego2map.dot(sensor2ego) + matrices.extend((sensor2ego, sensor2map)) if "CAM_TRAFFIC_LIGHT" in sensor_frame_id.value.upper(): - ego2tlr = HomogeneousMatrix( - sensor_position, sensor_rotation, src=FrameID.BASE_LINK, dst=FrameID.TRAFFIC_LIGHT - ) - tlr2map = ego2tlr.inv().dot(ego2map) - matrices.extend((ego2tlr, tlr2map)) + tlr_avg_pos.append(sensor_position) + tlr_avg_quat.append(sensor_rotation) + + # NOTE: Average positions and rotations are used for matrices of cameras related to TLR. + if len(tlr_avg_pos) > 0 and len(tlr_avg_quat) > 0: + tlr_cam_pos: NDArray = np.mean(tlr_avg_pos, axis=0) + tlr_cam_rot: Quaternion = sum(tlr_avg_quat) / sum(tlr_avg_quat).norm + tlr2ego = HomogeneousMatrix(tlr_cam_pos, tlr_cam_rot, src=FrameID.TRAFFIC_LIGHT, dst=FrameID.BASE_LINK) + tlr2map = ego2map.dot(tlr2ego) + matrices.extend((tlr2ego, tlr2map)) return matrices diff --git a/perception_eval/perception_eval/common/transform.py b/perception_eval/perception_eval/common/transform.py index 4b87f419..45e55ba1 100644 --- a/perception_eval/perception_eval/common/transform.py +++ b/perception_eval/perception_eval/common/transform.py @@ -333,18 +333,29 @@ def dot(self, other: HomogeneousMatrix) -> HomogeneousMatrix: Raises: ------- - ValueError: Expecting `self.dst` and `other.src` frame id is same. + ValueError: Expecting `self.src` and `other.dst` frame id is same. Returns: -------- HomogeneousMatrix: Result of dot product. + + Examples: + --------- + >>> ego2map = HomogeneousMatrix((1.0, 1.0, 1.0), (1.0, 0.0, 0.0, 0.0), src=FrameID.BASE_LINK, dst=FrameID.MAP) + >>> cam2ego = HomogeneousMatrix((2.0, 2.0, 2.0), (1.0, 0.0, 0.0, 0.0), src=FrameID.CAM_FRONT, dst=FrameID.BASE_LINK) + >>> cam2map = ego2map.dot(cam2ego) + >>> cam2map.matrix + array([[1., 0., 0., 3.], + [0., 1., 0., 3.], + [0., 0., 1., 3.], + [0., 0., 0., 1.]]) """ - if self.dst != other.src: - raise ValueError(f"self.dst != other.src: self.dst={self.dst}, other.src={other.src}") + if self.src != other.dst: + raise ValueError(f"self.src != other.dst: self.src={self.src}, other.dst={other.dst}") ret_mat = self.matrix.dot(other.matrix) position, rotation = self.__extract_position_and_rotation_from_matrix(ret_mat) - return HomogeneousMatrix(position, rotation, src=self.src, dst=other.dst) + return HomogeneousMatrix(position, rotation, src=other.src, dst=self.dst) def inv(self) -> HomogeneousMatrix: """Return an inverse matrix. diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index f1661b88..838b5d0f 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -553,6 +553,8 @@ def _is_target_object( else: position_ = bev_distance_ = None + print(f"{position_=}, {bev_distance_=}") + if position_ is not None: if is_target and max_x_position_list is not None: max_x_position = ( diff --git a/perception_eval/test/common/test_transform.py b/perception_eval/test/common/test_transform.py index b3d3134f..a3dcda20 100644 --- a/perception_eval/test/common/test_transform.py +++ b/perception_eval/test/common/test_transform.py @@ -1,11 +1,12 @@ import numpy as np + from perception_eval.common.schema import FrameID from perception_eval.common.transform import HomogeneousMatrix from perception_eval.common.transform import TransformDict from perception_eval.common.transform import TransformKey -def test_homogeneous_matrix(): +def test_homogeneous_matrix_transform(): ego2map = HomogeneousMatrix((1, 0, 0), (1, 0, 0, 0), src=FrameID.BASE_LINK, dst=FrameID.MAP) pos1 = ego2map.transform((1, 0, 0)) assert np.allclose(pos1, np.array((2, 0, 0))) @@ -33,6 +34,31 @@ def test_homogeneous_matrix(): assert np.allclose(mat2.rotation_matrix, np.eye(3)) +def test_homogenous_matrix_dot(): + ego2map = HomogeneousMatrix((1, 1, 1), (1, 0, 0, 0), src=FrameID.BASE_LINK, dst=FrameID.MAP) + cam2ego = HomogeneousMatrix((2, 2, 2), (1, 0, 0, 0), src=FrameID.CAM_FRONT, dst=FrameID.BASE_LINK) + cam2map = ego2map.dot(cam2ego) + assert np.allclose( + cam2map.matrix, + np.array( + [ + [1, 0, 0, 3], + [0, 1, 0, 3], + [0, 0, 1, 3], + [0, 0, 0, 1], + ], + ), + ) + assert np.allclose(cam2map.position, np.array([3, 3, 3])) # cam position in map coords + assert np.allclose(cam2map.rotation, np.eye(3)) # cam rotation matrix in map coords + assert cam2map.src == FrameID.CAM_FRONT + assert cam2map.dst == FrameID.MAP + + +def test_homogenous_matrix_inv(): + pass + + def test_transform_dict(): ego2map = HomogeneousMatrix((1, 0, 0), (1, 0, 0, 0), src=FrameID.BASE_LINK, dst=FrameID.MAP) transforms = TransformDict(ego2map) From 7e2fbc4304d7af75217ca45ed72873568a42257e Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 23 May 2024 05:45:02 +0000 Subject: [PATCH 25/27] style(pre-commit): autofix --- perception_eval/perception_eval/common/dataset_utils.py | 5 ++--- perception_eval/test/common/test_transform.py | 1 - 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index 3f7e8928..e3d1d13b 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -29,9 +29,6 @@ from nuscenes.nuscenes import NuScenes from nuscenes.prediction.helper import PredictHelper from nuscenes.utils.data_classes import Box -from PIL import Image -from pyquaternion.quaternion import Quaternion - from perception_eval.common.evaluation_task import EvaluationTask from perception_eval.common.label import Label from perception_eval.common.label import LabelConverter @@ -44,6 +41,8 @@ from perception_eval.common.shape import Shape from perception_eval.common.shape import ShapeType from perception_eval.common.transform import HomogeneousMatrix +from PIL import Image +from pyquaternion.quaternion import Quaternion from . import dataset diff --git a/perception_eval/test/common/test_transform.py b/perception_eval/test/common/test_transform.py index 58e287f5..dbb7b556 100644 --- a/perception_eval/test/common/test_transform.py +++ b/perception_eval/test/common/test_transform.py @@ -1,5 +1,4 @@ import numpy as np - from perception_eval.common.schema import FrameID from perception_eval.common.transform import HomogeneousMatrix from perception_eval.common.transform import TransformDict From b354e8af6fb00641a9d9772c792fa6832983e23d Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 28 May 2024 09:24:05 +0900 Subject: [PATCH 26/27] chore: rename `FrameID.TRAFFIC_LIGHT` to `FrameID.CAM_TRAFFIC_LIGHT` Signed-off-by: ktro2828 --- perception_eval/perception_eval/common/dataset_utils.py | 6 +++--- perception_eval/perception_eval/common/schema.py | 2 +- .../perception_eval/evaluation/matching/objects_filter.py | 2 -- .../perception_eval/evaluation/result/object_result.py | 5 ++++- 4 files changed, 8 insertions(+), 7 deletions(-) diff --git a/perception_eval/perception_eval/common/dataset_utils.py b/perception_eval/perception_eval/common/dataset_utils.py index e3d1d13b..4c77e7d1 100644 --- a/perception_eval/perception_eval/common/dataset_utils.py +++ b/perception_eval/perception_eval/common/dataset_utils.py @@ -286,7 +286,7 @@ def _get_transforms(nusc: NuScenes, sample_data_token: str) -> List[HomogeneousM if len(tlr_avg_pos) > 0 and len(tlr_avg_quat) > 0: tlr_cam_pos: NDArray = np.mean(tlr_avg_pos, axis=0) tlr_cam_rot: Quaternion = sum(tlr_avg_quat) / sum(tlr_avg_quat).norm - tlr2ego = HomogeneousMatrix(tlr_cam_pos, tlr_cam_rot, src=FrameID.TRAFFIC_LIGHT, dst=FrameID.BASE_LINK) + tlr2ego = HomogeneousMatrix(tlr_cam_pos, tlr_cam_rot, src=FrameID.CAM_TRAFFIC_LIGHT, dst=FrameID.BASE_LINK) tlr2map = ego2map.dot(tlr2ego) matrices.extend((tlr2ego, tlr2map)) @@ -575,7 +575,7 @@ def _merge_duplicated_traffic_lights( objects: List[DynamicObject2D], uuids: List[str], ) -> List[DynamicObject2D]: - """Merge traffic light objects which have same uuids and set its frame id as `FrameID.TRAFFIC_LIGHT`. + """Merge traffic light objects which have same uuids and set its frame id as `FrameID.CAM_TRAFFIC_LIGHT`. Args: unix_time (int): Current unix timestamp. @@ -604,7 +604,7 @@ def _merge_duplicated_traffic_lights( assert semantic_label.label != TrafficLightLabel.UNKNOWN merged_object = DynamicObject2D( unix_time=unix_time, - frame_id=FrameID.TRAFFIC_LIGHT, + frame_id=FrameID.CAM_TRAFFIC_LIGHT, semantic_score=1.0, semantic_label=semantic_label, roi=None, diff --git a/perception_eval/perception_eval/common/schema.py b/perception_eval/perception_eval/common/schema.py index ccef702c..54714bfb 100644 --- a/perception_eval/perception_eval/common/schema.py +++ b/perception_eval/perception_eval/common/schema.py @@ -48,7 +48,7 @@ class FrameID(Enum): CAM_TRAFFIC_LIGHT_FAR = "cam_traffic_light_far" # Integrated TLR camera frame - TRAFFIC_LIGHT = "traffic_light" + CAM_TRAFFIC_LIGHT = "cam_traffic_light" def __hash__(self) -> int: return hash(self.value) diff --git a/perception_eval/perception_eval/evaluation/matching/objects_filter.py b/perception_eval/perception_eval/evaluation/matching/objects_filter.py index 838b5d0f..f1661b88 100644 --- a/perception_eval/perception_eval/evaluation/matching/objects_filter.py +++ b/perception_eval/perception_eval/evaluation/matching/objects_filter.py @@ -553,8 +553,6 @@ def _is_target_object( else: position_ = bev_distance_ = None - print(f"{position_=}, {bev_distance_=}") - if position_ is not None: if is_target and max_x_position_list is not None: max_x_position = ( diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index 036a16eb..c1ab4e28 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -20,6 +20,7 @@ from typing import Tuple import numpy as np + from perception_eval.common import distance_objects from perception_eval.common import distance_objects_bev from perception_eval.common import DynamicObject @@ -396,7 +397,9 @@ def _get_object_results_with_id( ground_truth_objects_.remove(gt_object) # when there are rest of estimated objects, they all are FP. - if len(estimated_objects_) > 0 and not any([est.frame_id == FrameID.TRAFFIC_LIGHT for est in estimated_objects_]): + if len(estimated_objects_) > 0 and not any( + [est.frame_id == FrameID.CAM_TRAFFIC_LIGHT for est in estimated_objects_] + ): object_results += _get_fp_object_results(estimated_objects_) return object_results From 99437575d29c67ae73e0a7fd4e130170896f5439 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 28 May 2024 00:36:27 +0000 Subject: [PATCH 27/27] style(pre-commit): autofix --- .../perception_eval/evaluation/result/object_result.py | 1 - 1 file changed, 1 deletion(-) diff --git a/perception_eval/perception_eval/evaluation/result/object_result.py b/perception_eval/perception_eval/evaluation/result/object_result.py index c1ab4e28..a2ecf58d 100644 --- a/perception_eval/perception_eval/evaluation/result/object_result.py +++ b/perception_eval/perception_eval/evaluation/result/object_result.py @@ -20,7 +20,6 @@ from typing import Tuple import numpy as np - from perception_eval.common import distance_objects from perception_eval.common import distance_objects_bev from perception_eval.common import DynamicObject