Skip to content

Commit e9c1ac0

Browse files
committed
Merge branch 'develop' into feat/#389-set-initial-pose-directly
2 parents 40d160d + 6a21162 commit e9c1ac0

18 files changed

+410
-151
lines changed

.driving_log_replayer.cspell.json

+2
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@
2424
"Minoda",
2525
"pyproject",
2626
"CENTERDISTANCE",
27+
"rightdiagonal",
28+
"leftdiagonal",
2729
"nums",
2830
"pydantic",
2931
"Kotaro",

.vscode/settings.json

+5-2
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,8 @@
3939
"${env:HOME}/ros_ws/awf/install/tier4_api_msgs/local/lib/python3.10/dist-packages",
4040
"${env:HOME}/ros_ws/awf/install/tier4_perception_msgs/local/lib/python3.10/dist-packages",
4141
"${env:HOME}/ros_ws/awf/install/lanelet2_extension_python/local/lib/python3.10/dist-packages",
42-
"${env:HOME}/ros_ws/awf/install/autoware_common_msgs/local/lib/python3.10/dist-packages"
42+
"${env:HOME}/ros_ws/awf/install/autoware_common_msgs/local/lib/python3.10/dist-packages",
43+
"${env:HOME}/ros_ws/awf/install/autoware_perception_msgs/local/lib/python3.10/dist-packages",
4344
],
4445
"python.analysis.extraPaths": [
4546
"/opt/ros/humble/lib/python3.10/site-packages",
@@ -56,7 +57,9 @@
5657
"${env:HOME}/ros_ws/awf/install/tier4_api_msgs/local/lib/python3.10/dist-packages",
5758
"${env:HOME}/ros_ws/awf/install/tier4_perception_msgs/local/lib/python3.10/dist-packages",
5859
"${env:HOME}/ros_ws/awf/install/lanelet2_extension_python/local/lib/python3.10/dist-packages",
59-
"${env:HOME}/ros_ws/awf/install/autoware_common_msgs/local/lib/python3.10/dist-packages"
60+
"${env:HOME}/ros_ws/awf/install/autoware_common_msgs/local/lib/python3.10/dist-packages",
61+
"${env:HOME}/ros_ws/awf/install/autoware_perception_msgs/local/lib/python3.10/dist-packages",
62+
"${env:HOME}/ros_ws/awf/install/lanelet2_extension_python/local/lib/python3.10/dist-packages"
6063
],
6164
"files.associations": {
6265
"cctype": "cpp",

driving_log_replayer/driving_log_replayer/criteria/perception.py

+3-1
Original file line numberDiff line numberDiff line change
@@ -160,7 +160,9 @@ def from_str(cls, value: str) -> CriteriaMethod:
160160
161161
"""
162162
name: str = value.upper()
163-
assert name in cls.__members__, "value must be NUM_TP, METRICS_SCORE, or METRICS_SCORE_MAPH"
163+
assert (
164+
name in cls.__members__
165+
), "value must be NUM_TP, LABEL, METRICS_SCORE, or METRICS_SCORE_MAPH"
164166
return cls.__members__[name]
165167

166168

driving_log_replayer/driving_log_replayer/evaluator.py

+4-31
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,6 @@
1919
from typing import TYPE_CHECKING
2020

2121
from autoware_auto_perception_msgs.msg import ObjectClassification
22-
from autoware_auto_perception_msgs.msg import TrafficLight
2322
from builtin_interfaces.msg import Time as Stamp
2423
from geometry_msgs.msg import Point
2524
from geometry_msgs.msg import Pose
@@ -363,36 +362,10 @@ def get_most_probable_classification(
363362
cls,
364363
array_classification: list[ObjectClassification],
365364
) -> ObjectClassification:
366-
highest_probability = 0.0
367-
highest_classification = None
368-
for classification in array_classification:
369-
if classification.probability >= highest_probability:
370-
highest_probability = classification.probability
371-
highest_classification = classification
372-
return highest_classification
373-
374-
@classmethod
375-
def get_traffic_light_label_str(cls, light: TrafficLight) -> str:
376-
if light.color == TrafficLight.RED:
377-
return "red"
378-
if light.color == TrafficLight.AMBER:
379-
return "yellow"
380-
if light.color == TrafficLight.GREEN:
381-
return "green"
382-
return "unknown"
383-
384-
@classmethod
385-
def get_most_probable_signal(
386-
cls,
387-
lights: list[TrafficLight],
388-
) -> TrafficLight:
389-
highest_probability = 0.0
390-
highest_light = None
391-
for light in lights:
392-
if light.confidence >= highest_probability:
393-
highest_probability = light.confidence
394-
highest_light = light
395-
return highest_light
365+
index: int = array_classification.index(
366+
max(array_classification, key=lambda x: x.probability),
367+
)
368+
return array_classification[index]
396369

397370

398371
def evaluator_main(func: Callable) -> Callable:

driving_log_replayer/driving_log_replayer/lanelet2_util.py

+15-4
Original file line numberDiff line numberDiff line change
@@ -21,12 +21,23 @@
2121
from shapely.geometry import Polygon
2222

2323

24-
def road_lanelets_from_file(map_path: str) -> Any:
24+
def load_map(map_path: str) -> lanelet2.core.LaneletMap:
2525
projection = MGRSProjector(lanelet2.io.Origin(0.0, 0.0))
26-
lanelet_map = lanelet2.io.load(map_path, projection)
27-
all_lanelets = query.laneletLayer(lanelet_map)
26+
return lanelet2.io.load(map_path, projection)
27+
28+
29+
def load_all_lanelets(map_path: str) -> Any:
30+
lanelet_map = load_map(map_path)
31+
return query.laneletLayer(lanelet_map)
32+
33+
34+
def road_lanelets_from_file(map_path: str) -> Any:
2835
# return type lanelet2_extension_python._lanelet2_extension_python_boost_python_utility.lanelet::ConstLanelets
29-
return query.roadLanelets(all_lanelets)
36+
return query.roadLanelets(load_all_lanelets(map_path))
37+
38+
39+
def traffic_light_from_file(map_path: str) -> list:
40+
return query.trafficLights(load_all_lanelets(map_path))
3041

3142

3243
def to_shapely_polygon(lanelet: Lanelet) -> Polygon:

driving_log_replayer/driving_log_replayer/perception.py

+1-4
Original file line numberDiff line numberDiff line change
@@ -96,10 +96,7 @@ def __post_init__(self) -> None:
9696
distance_range=self.condition.Filter.Distance,
9797
)
9898

99-
def set_frame(
100-
self,
101-
frame: PerceptionFrameResult,
102-
) -> dict:
99+
def set_frame(self, frame: PerceptionFrameResult) -> dict:
103100
frame_success = "Fail"
104101
# ret_frame might be filtered frame result or original frame result.
105102
result, ret_frame = self.criteria.get_result(frame)

driving_log_replayer/driving_log_replayer/perception_eval_conversions.py

+5
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15+
from builtin_interfaces.msg import Time
1516
from geometry_msgs.msg import Point
1617
from geometry_msgs.msg import Polygon as RosPolygon
1718
from geometry_msgs.msg import Pose
@@ -36,6 +37,10 @@ def unix_time_from_ros_msg(ros_header: Header) -> int:
3637
return ros_header.stamp.sec * pow(10, 6) + ros_header.stamp.nanosec // 1000
3738

3839

40+
def unix_time_from_ros_timestamp(ros_timestamp: Time) -> int:
41+
return ros_timestamp.sec * pow(10, 6) + ros_timestamp.nanosec // 1000
42+
43+
3944
def position_from_ros_msg(ros_position: Point) -> tuple[int, int, int]:
4045
return (ros_position.x, ros_position.y, ros_position.z)
4146

driving_log_replayer/driving_log_replayer/traffic_light.py

+162-19
Original file line numberDiff line numberDiff line change
@@ -13,27 +13,136 @@
1313
# limitations under the License.
1414

1515
from dataclasses import dataclass
16+
import logging
17+
from pathlib import Path
18+
import sys
1619
from typing import Literal
1720

21+
from autoware_perception_msgs.msg import TrafficSignalElement
1822
from perception_eval.evaluation import PerceptionFrameResult
1923
from pydantic import BaseModel
24+
from pydantic import field_validator
25+
import simplejson as json
2026

2127
from driving_log_replayer.criteria import PerceptionCriteria
28+
from driving_log_replayer.perception_eval_conversions import summarize_pass_fail_result
2229
from driving_log_replayer.result import EvaluationItem
2330
from driving_log_replayer.result import ResultBase
2431
from driving_log_replayer.scenario import number
2532
from driving_log_replayer.scenario import Scenario
2633

34+
TRAFFIC_LIGHT_LABEL_MAPPINGS: list[tuple[set, str]] = [
35+
({"green"}, "green"),
36+
({"green", "straight"}, "green_straight"),
37+
({"green", "left"}, "green_left"),
38+
({"green", "right"}, "green_right"),
39+
({"yellow"}, "yellow"),
40+
({"yellow", "straight"}, "yellow_straight"),
41+
({"yellow", "left"}, "yellow_left"),
42+
({"yellow", "right"}, "yellow_right"),
43+
({"yellow", "straight", "left"}, "yellow_straight_left"),
44+
({"yellow", "straight", "right"}, "yellow_straight_right"),
45+
({"red"}, "red"),
46+
({"red", "straight"}, "red_straight"),
47+
({"red", "left"}, "red_left"),
48+
({"red", "right"}, "red_right"),
49+
({"red", "straight", "left"}, "red_straight_left"),
50+
({"red", "straight", "right"}, "red_straight_right"),
51+
({"red", "straight", "left", "right"}, "red_straight_left_right"),
52+
({"red", "right", "diagonal"}, "red_rightdiagonal"),
53+
({"red", "left", "diagonal"}, "red_leftdiagonal"),
54+
]
2755

28-
class Conditions(BaseModel):
56+
57+
def get_traffic_light_label_str(elements: list[TrafficSignalElement]) -> str: # noqa
58+
label_infos = []
59+
for element in elements:
60+
if element.shape == TrafficSignalElement.CIRCLE:
61+
if element.color == TrafficSignalElement.RED:
62+
label_infos.append("red")
63+
elif element.color == TrafficSignalElement.AMBER:
64+
label_infos.append("yellow")
65+
elif element.color == TrafficSignalElement.GREEN:
66+
label_infos.append("green")
67+
continue
68+
69+
if element.shape == TrafficSignalElement.UP_ARROW:
70+
label_infos.append("straight")
71+
elif element.shape == TrafficSignalElement.LEFT_ARROW:
72+
label_infos.append("left")
73+
elif element.shape == TrafficSignalElement.RIGHT_ARROW:
74+
label_infos.append("right")
75+
elif element.shape in (
76+
TrafficSignalElement.UP_LEFT_ARROW,
77+
TrafficSignalElement.DOWN_LEFT_ARROW,
78+
):
79+
label_infos.append("left")
80+
label_infos.append("diagonal")
81+
elif element.shape in (
82+
TrafficSignalElement.UP_RIGHT_ARROW,
83+
TrafficSignalElement.DOWN_RIGHT_ARROW,
84+
):
85+
label_infos.append("right")
86+
label_infos.append("diagonal")
87+
88+
label_infos = set(label_infos)
89+
90+
for info_set, label in TRAFFIC_LIGHT_LABEL_MAPPINGS:
91+
if label_infos == info_set:
92+
return label
93+
94+
return "unknown"
95+
96+
97+
def get_most_probable_element(
98+
elements: list[TrafficSignalElement],
99+
) -> TrafficSignalElement:
100+
index: int = elements.index(max(elements, key=lambda x: x.confidence))
101+
return elements[index]
102+
103+
104+
class Filter(BaseModel):
105+
Distance: tuple[float, float] | None = None
106+
# add filter condition here
107+
108+
@field_validator("Distance", mode="before")
109+
@classmethod
110+
def validate_distance_range(cls, v: str | None) -> tuple[number, number] | None:
111+
if v is None:
112+
return None
113+
114+
err_msg = f"{v} is not valid distance range, expected ordering min-max with min < max."
115+
116+
s_lower, s_upper = v.split("-")
117+
if s_upper == "":
118+
s_upper = sys.float_info.max
119+
120+
lower = float(s_lower)
121+
upper = float(s_upper)
122+
123+
if lower >= upper:
124+
raise ValueError(err_msg)
125+
return (lower, upper)
126+
127+
128+
class Criteria(BaseModel):
29129
PassRate: number
30-
CriteriaMethod: Literal["num_tp", "metrics_score"] | None = None
31-
CriteriaLevel: Literal["perfect", "hard", "normal", "easy"] | number | None = None
130+
CriteriaMethod: (
131+
Literal["num_tp", "label", "metrics_score", "metrics_score_maph"] | list[str] | None
132+
) = None
133+
CriteriaLevel: (
134+
Literal["perfect", "hard", "normal", "easy"] | list[str] | number | list[number] | None
135+
) = None
136+
Filter: Filter
137+
138+
139+
class Conditions(BaseModel):
140+
Criterion: list[Criteria]
32141

33142

34143
class Evaluation(BaseModel):
35144
UseCaseName: Literal["traffic_light"]
36-
UseCaseFormatVersion: Literal["0.2.0", "0.3.0"]
145+
UseCaseFormatVersion: Literal["1.0.0"]
37146
Datasets: list[dict]
38147
Conditions: Conditions
39148
PerceptionEvaluationConfig: dict
@@ -45,6 +154,36 @@ class TrafficLightScenario(Scenario):
45154
Evaluation: Evaluation
46155

47156

157+
class FailResultHolder:
158+
def __init__(self, save_dir: str) -> None:
159+
self.save_path: str = Path(save_dir, "fail_info.json")
160+
self.buffer = []
161+
162+
def add_frame(self, frame_result: PerceptionFrameResult) -> None:
163+
if frame_result.pass_fail_result.get_fail_object_num() <= 0:
164+
return
165+
info = {"fp": [], "fn": []}
166+
info["timestamp"] = frame_result.frame_ground_truth.unix_time
167+
for fp_result in frame_result.pass_fail_result.fp_object_results:
168+
est_label = fp_result.estimated_object.semantic_label.label.value
169+
gt_label = (
170+
fp_result.ground_truth_object.semantic_label.label.value
171+
if fp_result.ground_truth_object is not None
172+
else None
173+
)
174+
info["fp"].append({"est": est_label, "gt": gt_label})
175+
for fn_object in frame_result.pass_fail_result.fn_objects:
176+
info["fn"].append({"est": None, "gt": fn_object.semantic_label.label.value})
177+
178+
info_str = f"Fail timestamp: {info}"
179+
logging.info(info_str)
180+
self.buffer.append(info)
181+
182+
def save(self) -> None:
183+
with self.save_path.open("w") as f:
184+
json.dump(self.buffer, f, ensure_ascii=False, indent=4)
185+
186+
48187
@dataclass
49188
class Perception(EvaluationItem):
50189
success: bool = True
@@ -55,11 +194,12 @@ def __post_init__(self) -> None:
55194
self.criteria: PerceptionCriteria = PerceptionCriteria(
56195
methods=self.condition.CriteriaMethod,
57196
levels=self.condition.CriteriaLevel,
197+
distance_range=self.condition.Filter.Distance,
58198
)
59199

60200
def set_frame(self, frame: PerceptionFrameResult) -> dict:
61201
frame_success = "Fail"
62-
result, _ = self.criteria.get_result(frame)
202+
result, ret_frame = self.criteria.get_result(frame)
63203

64204
if result is None:
65205
self.no_gt_no_obj += 1
@@ -76,28 +216,30 @@ def set_frame(self, frame: PerceptionFrameResult) -> dict:
76216
return {
77217
"PassFail": {
78218
"Result": {"Total": self.success_str(), "Frame": frame_success},
79-
"Info": {
80-
"TP": len(frame.pass_fail_result.tp_object_results),
81-
"FP": len(frame.pass_fail_result.fp_object_results),
82-
"FN": len(frame.pass_fail_result.fn_objects),
83-
},
219+
"Info": summarize_pass_fail_result(ret_frame.pass_fail_result),
84220
},
85221
}
86222

87223

88224
class TrafficLightResult(ResultBase):
89225
def __init__(self, condition: Conditions) -> None:
90226
super().__init__()
91-
self.__perception = Perception(condition=condition)
227+
self.__perception_criterion: list[Perception] = []
228+
for i, criteria in enumerate(condition.Criterion):
229+
self.__perception_criterion.append(
230+
Perception(name=f"criteria{i}", condition=criteria),
231+
)
92232

93233
def update(self) -> None:
94-
summary_str = f"{self.__perception.summary}"
95-
if self.__perception.success:
96-
self._success = True
97-
self._summary = f"Passed: {summary_str}"
98-
else:
99-
self._success = False
100-
self._summary = f"Failed: {summary_str}"
234+
all_summary: list[str] = []
235+
all_success: list[bool] = []
236+
for criterion in self.__perception_criterion:
237+
tmp_success = criterion.success
238+
prefix_str = "Passed: " if tmp_success else "Failed: "
239+
all_summary.append(prefix_str + criterion.summary)
240+
all_success.append(tmp_success)
241+
self._summary = ", ".join(all_summary)
242+
self._success = all(all_success)
101243

102244
def set_frame(
103245
self,
@@ -110,7 +252,8 @@ def set_frame(
110252
"FrameName": frame.frame_name,
111253
"FrameSkip": skip,
112254
}
113-
self._frame |= self.__perception.set_frame(frame)
255+
for criterion in self.__perception_criterion:
256+
self._frame[criterion.name] = criterion.set_frame(frame)
114257
self.update()
115258

116259
def set_final_metrics(self, final_metrics: dict) -> None:

0 commit comments

Comments
 (0)